consistent naming scheme for SfM_Data
parent
8dc46669bb
commit
719975022c
|
@ -31,7 +31,7 @@ void createExampleBALFile(const string& filename, const vector<Point3>& P,
|
|||
Cal3Bundler()) {
|
||||
|
||||
// Class that will gather all data
|
||||
SfM_data data;
|
||||
SfM_Data data;
|
||||
|
||||
// Create two cameras
|
||||
Rot3 aRb = Rot3::Yaw(M_PI_2);
|
||||
|
|
|
@ -49,7 +49,7 @@ int main(int argc, char* argv[]) {
|
|||
filename = string(argv[1]);
|
||||
|
||||
// Load the SfM data from file
|
||||
SfM_data mydata;
|
||||
SfM_Data mydata;
|
||||
readBAL(filename, mydata);
|
||||
cout
|
||||
<< boost::format("read %1% tracks on %2% cameras\n")
|
||||
|
|
|
@ -42,7 +42,7 @@ int main (int argc, char* argv[]) {
|
|||
if (argc>1) filename = string(argv[1]);
|
||||
|
||||
// Load the SfM data from file
|
||||
SfM_data mydata;
|
||||
SfM_Data mydata;
|
||||
readBAL(filename, mydata);
|
||||
cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.number_tracks() % mydata.number_cameras();
|
||||
|
||||
|
|
|
@ -47,7 +47,7 @@ int main (int argc, char* argv[]) {
|
|||
if (argc>1) filename = string(argv[1]);
|
||||
|
||||
// Load the SfM data from file
|
||||
SfM_data mydata;
|
||||
SfM_Data mydata;
|
||||
readBAL(filename, mydata);
|
||||
cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.number_tracks() % mydata.number_cameras();
|
||||
|
||||
|
|
2
gtsam.h
2
gtsam.h
|
@ -2730,7 +2730,7 @@ class SfM_Track {
|
|||
pair<size_t, size_t> SIFT_index(size_t idx) const;
|
||||
};
|
||||
|
||||
class SfM_data {
|
||||
class SfM_Data {
|
||||
size_t number_cameras() const;
|
||||
size_t number_tracks() const;
|
||||
//TODO(Varun) Need to fix issue #237 first before this can work
|
||||
|
|
|
@ -646,7 +646,7 @@ Pose3 gtsam2openGL(const Pose3& PoseGTSAM) {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
bool readBundler(const string& filename, SfM_data &data) {
|
||||
bool readBundler(const string& filename, SfM_Data &data) {
|
||||
// Load the data file
|
||||
ifstream is(filename.c_str(), ifstream::in);
|
||||
if (!is) {
|
||||
|
@ -733,7 +733,7 @@ bool readBundler(const string& filename, SfM_data &data) {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
bool readBAL(const string& filename, SfM_data &data) {
|
||||
bool readBAL(const string& filename, SfM_Data &data) {
|
||||
// Load the data file
|
||||
ifstream is(filename.c_str(), ifstream::in);
|
||||
if (!is) {
|
||||
|
@ -793,7 +793,7 @@ bool readBAL(const string& filename, SfM_data &data) {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
bool writeBAL(const string& filename, SfM_data &data) {
|
||||
bool writeBAL(const string& filename, SfM_Data &data) {
|
||||
// Open the output file
|
||||
ofstream os;
|
||||
os.open(filename.c_str());
|
||||
|
@ -866,12 +866,12 @@ bool writeBAL(const string& filename, SfM_data &data) {
|
|||
return true;
|
||||
}
|
||||
|
||||
bool writeBALfromValues(const string& filename, const SfM_data &data,
|
||||
bool writeBALfromValues(const string& filename, const SfM_Data &data,
|
||||
Values& values) {
|
||||
using Camera = PinholeCamera<Cal3Bundler>;
|
||||
SfM_data dataValues = data;
|
||||
SfM_Data dataValues = data;
|
||||
|
||||
// Store poses or cameras in SfM_data
|
||||
// Store poses or cameras in SfM_Data
|
||||
size_t nrPoses = values.count<Pose3>();
|
||||
if (nrPoses == dataValues.number_cameras()) { // we only estimated camera poses
|
||||
for (size_t i = 0; i < dataValues.number_cameras(); i++) { // for each camera
|
||||
|
@ -899,7 +899,7 @@ bool writeBALfromValues(const string& filename, const SfM_data &data,
|
|||
}
|
||||
}
|
||||
|
||||
// Store 3D points in SfM_data
|
||||
// Store 3D points in SfM_Data
|
||||
size_t nrPoints = values.count<Point3>(), nrTracks = dataValues.number_tracks();
|
||||
if (nrPoints != nrTracks) {
|
||||
cout
|
||||
|
@ -921,11 +921,11 @@ bool writeBALfromValues(const string& filename, const SfM_data &data,
|
|||
}
|
||||
}
|
||||
|
||||
// Write SfM_data to file
|
||||
// Write SfM_Data to file
|
||||
return writeBAL(filename, dataValues);
|
||||
}
|
||||
|
||||
Values initialCamerasEstimate(const SfM_data& db) {
|
||||
Values initialCamerasEstimate(const SfM_Data& db) {
|
||||
Values initial;
|
||||
size_t i = 0; // NO POINTS: j = 0;
|
||||
for(const SfM_Camera& camera: db.cameras)
|
||||
|
@ -933,7 +933,7 @@ Values initialCamerasEstimate(const SfM_data& db) {
|
|||
return initial;
|
||||
}
|
||||
|
||||
Values initialCamerasAndPointsEstimate(const SfM_data& db) {
|
||||
Values initialCamerasAndPointsEstimate(const SfM_Data& db) {
|
||||
Values initial;
|
||||
size_t i = 0, j = 0;
|
||||
for(const SfM_Camera& camera: db.cameras)
|
||||
|
|
|
@ -197,7 +197,7 @@ struct SfM_Track {
|
|||
typedef PinholeCamera<Cal3Bundler> SfM_Camera;
|
||||
|
||||
/// Define the structure for SfM data
|
||||
struct SfM_data {
|
||||
struct SfM_Data {
|
||||
std::vector<SfM_Camera> cameras; ///< Set of cameras
|
||||
std::vector<SfM_Track> tracks; ///< Sparse set of points
|
||||
/// The number of camera poses
|
||||
|
@ -218,36 +218,39 @@ struct SfM_data {
|
|||
}
|
||||
};
|
||||
|
||||
/// Alias for backwards compatibility
|
||||
typedef SfM_Data SfM_data;
|
||||
|
||||
/**
|
||||
* @brief This function parses a bundler output file and stores the data into a
|
||||
* SfM_data structure
|
||||
* SfM_Data structure
|
||||
* @param filename The name of the bundler file
|
||||
* @param data SfM structure where the data is stored
|
||||
* @return true if the parsing was successful, false otherwise
|
||||
*/
|
||||
GTSAM_EXPORT bool readBundler(const std::string& filename, SfM_data &data);
|
||||
GTSAM_EXPORT bool readBundler(const std::string& filename, SfM_Data &data);
|
||||
|
||||
/**
|
||||
* @brief This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a
|
||||
* SfM_data structure
|
||||
* SfM_Data structure
|
||||
* @param filename The name of the BAL file
|
||||
* @param data SfM structure where the data is stored
|
||||
* @return true if the parsing was successful, false otherwise
|
||||
*/
|
||||
GTSAM_EXPORT bool readBAL(const std::string& filename, SfM_data &data);
|
||||
GTSAM_EXPORT bool readBAL(const std::string& filename, SfM_Data &data);
|
||||
|
||||
/**
|
||||
* @brief This function writes a "Bundle Adjustment in the Large" (BAL) file from a
|
||||
* SfM_data structure
|
||||
* SfM_Data structure
|
||||
* @param filename The name of the BAL file to write
|
||||
* @param data SfM structure where the data is stored
|
||||
* @return true if the parsing was successful, false otherwise
|
||||
*/
|
||||
GTSAM_EXPORT bool writeBAL(const std::string& filename, SfM_data &data);
|
||||
GTSAM_EXPORT bool writeBAL(const std::string& filename, SfM_Data &data);
|
||||
|
||||
/**
|
||||
* @brief This function writes a "Bundle Adjustment in the Large" (BAL) file from a
|
||||
* SfM_data structure and a value structure (measurements are the same as the SfM input data,
|
||||
* SfM_Data structure and a value structure (measurements are the same as the SfM input data,
|
||||
* while camera poses and values are read from Values)
|
||||
* @param filename The name of the BAL file to write
|
||||
* @param data SfM structure where the data is stored
|
||||
|
@ -257,7 +260,7 @@ GTSAM_EXPORT bool writeBAL(const std::string& filename, SfM_data &data);
|
|||
* @return true if the parsing was successful, false otherwise
|
||||
*/
|
||||
GTSAM_EXPORT bool writeBALfromValues(const std::string& filename,
|
||||
const SfM_data &data, Values& values);
|
||||
const SfM_Data &data, Values& values);
|
||||
|
||||
/**
|
||||
* @brief This function converts an openGL camera pose to an GTSAM camera pose
|
||||
|
@ -288,16 +291,16 @@ GTSAM_EXPORT Pose3 gtsam2openGL(const Pose3& PoseGTSAM);
|
|||
|
||||
/**
|
||||
* @brief This function creates initial values for cameras from db
|
||||
* @param SfM_data
|
||||
* @param SfM_Data
|
||||
* @return Values
|
||||
*/
|
||||
GTSAM_EXPORT Values initialCamerasEstimate(const SfM_data& db);
|
||||
GTSAM_EXPORT Values initialCamerasEstimate(const SfM_Data& db);
|
||||
|
||||
/**
|
||||
* @brief This function creates initial values for cameras and points from db
|
||||
* @param SfM_data
|
||||
* @param SfM_Data
|
||||
* @return Values
|
||||
*/
|
||||
GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfM_data& db);
|
||||
GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfM_Data& db);
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -106,7 +106,7 @@ TEST( dataSet, Balbianello)
|
|||
{
|
||||
///< The structure where we will save the SfM data
|
||||
const string filename = findExampleDataFile("Balbianello");
|
||||
SfM_data mydata;
|
||||
SfM_Data mydata;
|
||||
CHECK(readBundler(filename, mydata));
|
||||
|
||||
// Check number of things
|
||||
|
@ -389,7 +389,7 @@ TEST( dataSet, readBAL_Dubrovnik)
|
|||
{
|
||||
///< The structure where we will save the SfM data
|
||||
const string filename = findExampleDataFile("dubrovnik-3-7-pre");
|
||||
SfM_data mydata;
|
||||
SfM_Data mydata;
|
||||
CHECK(readBAL(filename, mydata));
|
||||
|
||||
// Check number of things
|
||||
|
@ -444,7 +444,7 @@ TEST( dataSet, writeBAL_Dubrovnik)
|
|||
{
|
||||
///< Read a file using the unit tested readBAL
|
||||
const string filenameToRead = findExampleDataFile("dubrovnik-3-7-pre");
|
||||
SfM_data readData;
|
||||
SfM_Data readData;
|
||||
readBAL(filenameToRead, readData);
|
||||
|
||||
// Write readData to file filenameToWrite
|
||||
|
@ -452,7 +452,7 @@ TEST( dataSet, writeBAL_Dubrovnik)
|
|||
CHECK(writeBAL(filenameToWrite, readData));
|
||||
|
||||
// Read what we wrote
|
||||
SfM_data writtenData;
|
||||
SfM_Data writtenData;
|
||||
CHECK(readBAL(filenameToWrite, writtenData));
|
||||
|
||||
// Check that what we read is the same as what we wrote
|
||||
|
@ -492,7 +492,7 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){
|
|||
|
||||
///< Read a file using the unit tested readBAL
|
||||
const string filenameToRead = findExampleDataFile("dubrovnik-3-7-pre");
|
||||
SfM_data readData;
|
||||
SfM_Data readData;
|
||||
readBAL(filenameToRead, readData);
|
||||
|
||||
Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.3,0.1,0.3));
|
||||
|
@ -514,7 +514,7 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){
|
|||
writeBALfromValues(filenameToWrite, readData, value);
|
||||
|
||||
// Read the file we wrote
|
||||
SfM_data writtenData;
|
||||
SfM_Data writtenData;
|
||||
readBAL(filenameToWrite, writtenData);
|
||||
|
||||
// Check that the reprojection errors are the same and the poses are correct
|
||||
|
|
|
@ -34,7 +34,7 @@ gtsam::Rot3 cRb = gtsam::Rot3(bX, bZ, -bY).inverse();
|
|||
namespace example1 {
|
||||
|
||||
const string filename = findExampleDataFile("5pointExample1.txt");
|
||||
SfM_data data;
|
||||
SfM_Data data;
|
||||
bool readOK = readBAL(filename, data);
|
||||
Rot3 c1Rc2 = data.cameras[1].pose().rotation();
|
||||
Point3 c1Tc2 = data.cameras[1].pose().translation();
|
||||
|
@ -357,7 +357,7 @@ TEST (EssentialMatrixFactor3, minimization) {
|
|||
namespace example2 {
|
||||
|
||||
const string filename = findExampleDataFile("5pointExample2.txt");
|
||||
SfM_data data;
|
||||
SfM_Data data;
|
||||
bool readOK = readBAL(filename, data);
|
||||
Rot3 aRb = data.cameras[1].pose().rotation();
|
||||
Point3 aTb = data.cameras[1].pose().translation();
|
||||
|
|
|
@ -42,7 +42,7 @@ using symbol_shorthand::P;
|
|||
/* ************************************************************************* */
|
||||
TEST(PinholeCamera, BAL) {
|
||||
string filename = findExampleDataFile("dubrovnik-3-7-pre");
|
||||
SfM_data db;
|
||||
SfM_Data db;
|
||||
bool success = readBAL(filename, db);
|
||||
if (!success) throw runtime_error("Could not access file!");
|
||||
|
||||
|
|
|
@ -32,7 +32,7 @@ typedef GeneralSFMFactor<Camera, Point3> SfmFactor;
|
|||
|
||||
int main(int argc, char* argv[]) {
|
||||
// parse options and read BAL file
|
||||
SfM_data db = preamble(argc, argv);
|
||||
SfM_Data db = preamble(argc, argv);
|
||||
|
||||
// Build graph using conventional GeneralSFMFactor
|
||||
NonlinearFactorGraph graph;
|
||||
|
|
|
@ -38,7 +38,7 @@ static bool gUseSchur = true;
|
|||
static SharedNoiseModel gNoiseModel = noiseModel::Unit::Create(2);
|
||||
|
||||
// parse options and read BAL file
|
||||
SfM_data preamble(int argc, char* argv[]) {
|
||||
SfM_Data preamble(int argc, char* argv[]) {
|
||||
// primitive argument parsing:
|
||||
if (argc > 2) {
|
||||
if (strcmp(argv[1], "--colamd"))
|
||||
|
@ -48,7 +48,7 @@ SfM_data preamble(int argc, char* argv[]) {
|
|||
}
|
||||
|
||||
// Load BAL file
|
||||
SfM_data db;
|
||||
SfM_Data db;
|
||||
string filename;
|
||||
if (argc > 1)
|
||||
filename = argv[argc - 1];
|
||||
|
@ -60,7 +60,7 @@ SfM_data preamble(int argc, char* argv[]) {
|
|||
}
|
||||
|
||||
// Create ordering and optimize
|
||||
int optimize(const SfM_data& db, const NonlinearFactorGraph& graph,
|
||||
int optimize(const SfM_Data& db, const NonlinearFactorGraph& graph,
|
||||
const Values& initial, bool separateCalibration = false) {
|
||||
using symbol_shorthand::P;
|
||||
|
||||
|
|
|
@ -38,7 +38,7 @@ typedef PinholeCamera<Cal3Bundler> Camera;
|
|||
|
||||
int main(int argc, char* argv[]) {
|
||||
// parse options and read BAL file
|
||||
SfM_data db = preamble(argc, argv);
|
||||
SfM_Data db = preamble(argc, argv);
|
||||
|
||||
AdaptAutoDiff<SnavelyProjection, 2, 9, 3> snavely;
|
||||
|
||||
|
|
|
@ -29,7 +29,7 @@ using namespace gtsam;
|
|||
|
||||
int main(int argc, char* argv[]) {
|
||||
// parse options and read BAL file
|
||||
SfM_data db = preamble(argc, argv);
|
||||
SfM_Data db = preamble(argc, argv);
|
||||
|
||||
// Build graph using conventional GeneralSFMFactor
|
||||
NonlinearFactorGraph graph;
|
||||
|
|
|
@ -29,7 +29,7 @@ using namespace gtsam;
|
|||
|
||||
int main(int argc, char* argv[]) {
|
||||
// parse options and read BAL file
|
||||
SfM_data db = preamble(argc, argv);
|
||||
SfM_Data db = preamble(argc, argv);
|
||||
|
||||
// Build graph using conventional GeneralSFMFactor
|
||||
NonlinearFactorGraph graph;
|
||||
|
|
|
@ -31,7 +31,7 @@ typedef SmartProjectionFactor<Camera> SfmFactor;
|
|||
|
||||
int main(int argc, char* argv[]) {
|
||||
// parse options and read BAL file
|
||||
SfM_data db = preamble(argc, argv);
|
||||
SfM_Data db = preamble(argc, argv);
|
||||
|
||||
// Add smart factors to graph
|
||||
NonlinearFactorGraph graph;
|
||||
|
|
Loading…
Reference in New Issue