gtsam/gtsam/slam/dataset.cpp

915 lines
29 KiB
C++
Raw Normal View History

/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file dataset.cpp
* @date Jan 22, 2010
* @author nikai, Luca Carlone
* @brief utility functions for loading datasets
2010-01-23 04:18:40 +08:00
*/
2015-07-13 09:57:26 +08:00
#include <gtsam/sam/BearingRangeFactor.h>
2015-06-08 11:24:45 +08:00
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/slam/dataset.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Pose2.h>
2015-06-08 11:24:45 +08:00
#include <gtsam/geometry/Rot3.h>
#include <gtsam/inference/FactorGraph.h>
#include <gtsam/inference/Symbol.h>
2015-06-08 11:24:45 +08:00
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/Values-inl.h>
#include <gtsam/linear/Sampler.h>
#include <gtsam/base/GenericValue.h>
#include <gtsam/base/Lie.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/types.h>
#include <gtsam/base/Value.h>
#include <gtsam/base/Vector.h>
2015-06-08 11:24:45 +08:00
#include <boost/assign/list_inserter.hpp>
#include <boost/filesystem/operations.hpp>
#include <boost/filesystem/path.hpp>
#include <boost/foreach.hpp>
2015-06-08 11:24:45 +08:00
#include <cmath>
#include <fstream>
2015-06-08 11:24:45 +08:00
#include <iostream>
#include <stdexcept>
2010-01-23 04:18:40 +08:00
using namespace std;
namespace fs = boost::filesystem;
using namespace gtsam::symbol_shorthand;
2010-01-23 04:18:40 +08:00
#define LINESIZE 81920
namespace gtsam {
#ifndef MATLAB_MEX_FILE
/* ************************************************************************* */
string findExampleDataFile(const string& name) {
// Search source tree and installed location
vector<string> rootsToSearch;
rootsToSearch.push_back(GTSAM_SOURCE_TREE_DATASET_DIR); // Defined by CMake, see gtsam/gtsam/CMakeLists.txt
2014-06-01 06:08:02 +08:00
rootsToSearch.push_back(GTSAM_INSTALLED_DATASET_DIR); // Defined by CMake, see gtsam/gtsam/CMakeLists.txt
// Search for filename as given, and with .graph and .txt extensions
vector<string> namesToSearch;
namesToSearch.push_back(name);
namesToSearch.push_back(name + ".graph");
namesToSearch.push_back(name + ".txt");
namesToSearch.push_back(name + ".out");
// Find first name that exists
BOOST_FOREACH(const fs::path& root, rootsToSearch) {
BOOST_FOREACH(const fs::path& name, namesToSearch) {
2014-06-01 06:08:02 +08:00
if (fs::is_regular_file(root / name))
return (root / name).string();
}
}
// If we did not return already, then we did not find the file
2014-06-01 06:08:02 +08:00
throw
invalid_argument(
2014-06-01 06:08:02 +08:00
"gtsam::findExampleDataFile could not find a matching file in\n"
2015-05-14 13:26:24 +08:00
GTSAM_SOURCE_TREE_DATASET_DIR " or\n"
GTSAM_INSTALLED_DATASET_DIR " named\n" +
2014-06-01 06:08:02 +08:00
name + ", " + name + ".graph, or " + name + ".txt");
}
2014-06-01 03:53:41 +08:00
2014-06-01 04:13:29 +08:00
/* ************************************************************************* */
2014-06-01 03:53:41 +08:00
string createRewrittenFileName(const string& name) {
// Search source tree and installed location
2014-06-01 06:08:02 +08:00
if (!exists(fs::path(name))) {
throw invalid_argument(
2014-06-01 06:08:02 +08:00
"gtsam::createRewrittenFileName could not find a matching file in\n"
+ name);
2014-06-01 03:53:41 +08:00
}
2014-06-01 06:08:02 +08:00
fs::path p(name);
fs::path newpath = fs::path(p.parent_path().string())
/ fs::path(p.stem().string() + "-rewritten.txt");
2014-06-01 03:53:41 +08:00
2014-06-01 06:08:02 +08:00
return newpath.string();
2014-06-01 03:53:41 +08:00
}
2014-06-01 04:13:29 +08:00
/* ************************************************************************* */
#endif
/* ************************************************************************* */
GraphAndValues load2D(pair<string, SharedNoiseModel> dataset, int maxID,
bool addNoise, bool smart, NoiseFormat noiseFormat,
KernelFunctionType kernelFunctionType) {
return load2D(dataset.first, dataset.second, maxID, addNoise, smart,
noiseFormat, kernelFunctionType);
}
/* ************************************************************************* */
// Read noise parameters and interpret them according to flags
static SharedNoiseModel readNoiseModel(ifstream& is, bool smart,
NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) {
double v1, v2, v3, v4, v5, v6;
is >> v1 >> v2 >> v3 >> v4 >> v5 >> v6;
if (noiseFormat == NoiseFormatAUTO)
{
// Try to guess covariance matrix layout
if(v1 != 0.0 && v2 == 0.0 && v3 != 0.0 && v4 != 0.0 && v5 == 0.0 && v6 == 0.0)
{
// NoiseFormatGRAPH
noiseFormat = NoiseFormatGRAPH;
}
else if(v1 != 0.0 && v2 == 0.0 && v3 == 0.0 && v4 != 0.0 && v5 == 0.0 && v6 != 0.0)
{
// NoiseFormatCOV
noiseFormat = NoiseFormatCOV;
}
else
{
throw std::invalid_argument("load2D: unrecognized covariance matrix format in dataset file. Please specify the noise format.");
}
}
// Read matrix and check that diagonal entries are non-zero
Matrix M(3, 3);
switch (noiseFormat) {
case NoiseFormatG2O:
case NoiseFormatCOV:
// i.e., [ v1 v2 v3; v2' v4 v5; v3' v5' v6 ]
if (v1 == 0.0 || v4 == 0.0 || v6 == 0.0)
throw runtime_error(
"load2D::readNoiseModel looks like this is not G2O matrix order");
M << v1, v2, v3, v2, v4, v5, v3, v5, v6;
break;
case NoiseFormatTORO:
case NoiseFormatGRAPH:
// http://www.openslam.org/toro.html
// inf_ff inf_fs inf_ss inf_rr inf_fr inf_sr
// i.e., [ v1 v2 v5; v2' v3 v6; v5' v6' v4 ]
if (v1 == 0.0 || v3 == 0.0 || v4 == 0.0)
throw invalid_argument(
"load2D::readNoiseModel looks like this is not TORO matrix order");
M << v1, v2, v5, v2, v3, v6, v5, v6, v4;
break;
default:
throw runtime_error("load2D: invalid noise format");
}
// Now, create a Gaussian noise model
// The smart flag will try to detect a simpler model, e.g., unit
SharedNoiseModel model;
switch (noiseFormat) {
case NoiseFormatG2O:
case NoiseFormatTORO:
// In both cases, what is stored in file is the information matrix
model = noiseModel::Gaussian::Information(M, smart);
break;
case NoiseFormatGRAPH:
case NoiseFormatCOV:
// These cases expect covariance matrix
model = noiseModel::Gaussian::Covariance(M, smart);
break;
default:
throw invalid_argument("load2D: invalid noise format");
}
switch (kernelFunctionType) {
case KernelFunctionTypeNONE:
return model;
break;
case KernelFunctionTypeHUBER:
return noiseModel::Robust::Create(
noiseModel::mEstimator::Huber::Create(1.345), model);
break;
case KernelFunctionTypeTUKEY:
return noiseModel::Robust::Create(
noiseModel::mEstimator::Tukey::Create(4.6851), model);
break;
default:
throw invalid_argument("load2D: invalid kernel function type");
}
}
2010-01-23 04:18:40 +08:00
/* ************************************************************************* */
2014-10-15 05:00:03 +08:00
GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID,
bool addNoise, bool smart, NoiseFormat noiseFormat,
KernelFunctionType kernelFunctionType) {
ifstream is(filename.c_str());
if (!is)
throw invalid_argument("load2D: can not find file " + filename);
Values::shared_ptr initial(new Values);
NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph);
string tag;
// load the poses
2014-08-22 22:40:16 +08:00
while (!is.eof()) {
2014-06-01 06:08:02 +08:00
if (!(is >> tag))
break;
2014-06-01 11:15:11 +08:00
if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) {
2014-08-26 04:36:58 +08:00
Key id;
double x, y, yaw;
is >> id >> x >> y >> yaw;
// optional filter
if (maxID && id >= maxID)
continue;
initial->insert(id, Pose2(x, y, yaw));
}
is.ignore(LINESIZE, '\n');
}
is.clear(); /* clears the end-of-file and error flags */
is.seekg(0, ios::beg);
// If asked, create a sampler with random number generator
Sampler sampler;
if (addNoise) {
noiseModel::Diagonal::shared_ptr noise;
if (model)
noise = boost::dynamic_pointer_cast<noiseModel::Diagonal>(model);
if (!noise)
throw invalid_argument(
"gtsam::load2D: invalid noise model for adding noise"
"(current version assumes diagonal noise model)!");
sampler = Sampler(noise);
}
// Parse the pose constraints
2014-10-15 05:00:03 +08:00
Key id1, id2;
bool haveLandmark = false;
2015-08-12 03:25:35 +08:00
const bool useModelInFile = !model;
2014-08-22 22:40:16 +08:00
while (!is.eof()) {
2014-06-01 06:08:02 +08:00
if (!(is >> tag))
break;
if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2")
|| (tag == "ODOMETRY")) {
2012-08-25 06:02:40 +08:00
// Read transform
double x, y, yaw;
2012-08-25 06:02:40 +08:00
is >> id1 >> id2 >> x >> y >> yaw;
Pose2 l1Xl2(x, y, yaw);
// read noise model
SharedNoiseModel modelInFile = readNoiseModel(is, smart, noiseFormat,
kernelFunctionType);
2012-08-25 06:02:40 +08:00
// optional filter
if (maxID && (id1 >= maxID || id2 >= maxID))
continue;
2015-08-12 03:25:35 +08:00
if (useModelInFile)
model = modelInFile;
2012-08-25 06:02:40 +08:00
if (addNoise)
l1Xl2 = l1Xl2.retract(sampler.sample());
2012-08-25 06:02:40 +08:00
// Insert vertices if pure odometry file
if (!initial->exists(id1))
initial->insert(id1, Pose2());
if (!initial->exists(id2))
initial->insert(id2, initial->at<Pose2>(id1) * l1Xl2);
NonlinearFactor::shared_ptr factor(
new BetweenFactor<Pose2>(id1, id2, l1Xl2, model));
2012-08-25 06:02:40 +08:00
graph->push_back(factor);
}
// Parse measurements
double bearing, range, bearing_std, range_std;
2012-08-25 06:02:40 +08:00
// A bearing-range measurement
if (tag == "BR") {
is >> id1 >> id2 >> bearing >> range >> bearing_std >> range_std;
2012-08-25 06:02:40 +08:00
}
// A landmark measurement, TODO Frank says: don't know why is converted to bearing-range
if (tag == "LANDMARK") {
double lmx, lmy;
double v1, v2, v3;
is >> id1 >> id2 >> lmx >> lmy >> v1 >> v2 >> v3;
// Convert x,y to bearing,range
bearing = atan2(lmy, lmx);
range = sqrt(lmx * lmx + lmy * lmy);
// In our experience, the x-y covariance on landmark sightings is not very good, so assume
// it describes the uncertainty at a range of 10m, and convert that to bearing/range uncertainty.
2014-06-01 06:08:02 +08:00
if (std::abs(v1 - v3) < 1e-4) {
bearing_std = sqrt(v1 / 10.0);
range_std = sqrt(v1);
2014-06-01 06:08:02 +08:00
} else {
bearing_std = 1;
range_std = 1;
2014-06-01 06:08:02 +08:00
if (!haveLandmark) {
cout
<< "Warning: load2D is a very simple dataset loader and is ignoring the\n"
"non-uniform covariance on LANDMARK measurements in this file."
<< endl;
haveLandmark = true;
}
}
}
// Do some common stuff for bearing-range measurements
if (tag == "LANDMARK" || tag == "BR") {
// optional filter
if (maxID && id1 >= maxID)
continue;
// Create noise model
noiseModel::Diagonal::shared_ptr measurementNoise =
noiseModel::Diagonal::Sigmas((Vector(2) << bearing_std, range_std).finished());
// Add to graph
*graph += BearingRangeFactor<Pose2, Point2>(id1, L(id2), bearing, range,
measurementNoise);
// Insert poses or points if they do not exist yet
if (!initial->exists(id1))
initial->insert(id1, Pose2());
if (!initial->exists(L(id2))) {
Pose2 pose = initial->at<Pose2>(id1);
2014-06-01 06:08:02 +08:00
Point2 local(cos(bearing) * range, sin(bearing) * range);
Point2 global = pose.transform_from(local);
initial->insert(L(id2), global);
}
}
is.ignore(LINESIZE, '\n');
}
return make_pair(graph, initial);
}
2010-01-23 04:18:40 +08:00
/* ************************************************************************* */
GraphAndValues load2D_robust(const string& filename,
noiseModel::Base::shared_ptr& model, int maxID) {
return load2D(filename, model, maxID);
}
/* ************************************************************************* */
void save2D(const NonlinearFactorGraph& graph, const Values& config,
const noiseModel::Diagonal::shared_ptr model, const string& filename) {
fstream stream(filename.c_str(), fstream::out);
// save poses
2014-11-02 02:23:07 +08:00
2014-06-01 06:08:02 +08:00
BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, config) {
2014-11-02 02:23:07 +08:00
const Pose2& pose = key_value.value.cast<Pose2>();
2014-06-01 06:08:02 +08:00
stream << "VERTEX2 " << key_value.key << " " << pose.x() << " " << pose.y()
<< " " << pose.theta() << endl;
}
// save edges
Matrix R = model->R();
Matrix RR = trans(R) * R; //prod(trans(R),R);
2014-06-01 06:08:02 +08:00
BOOST_FOREACH(boost::shared_ptr<NonlinearFactor> factor_, graph) {
boost::shared_ptr<BetweenFactor<Pose2> > factor =
boost::dynamic_pointer_cast<BetweenFactor<Pose2> >(factor_);
if (!factor)
continue;
2014-05-21 04:56:01 +08:00
Pose2 pose = factor->measured().inverse();
stream << "EDGE2 " << factor->key2() << " " << factor->key1() << " "
2014-06-01 06:08:02 +08:00
<< pose.x() << " " << pose.y() << " " << pose.theta() << " " << RR(0, 0)
<< " " << RR(0, 1) << " " << RR(1, 1) << " " << RR(2, 2) << " "
<< RR(0, 2) << " " << RR(1, 2) << endl;
}
stream.close();
}
/* ************************************************************************* */
GraphAndValues readG2o(const string& g2oFile, const bool is3D,
KernelFunctionType kernelFunctionType) {
// just call load2D
int maxID = 0;
bool addNoise = false;
bool smart = true;
if(is3D)
return load3D(g2oFile);
return load2D(g2oFile, SharedNoiseModel(), maxID, addNoise, smart,
NoiseFormatG2O, kernelFunctionType);
}
/* ************************************************************************* */
void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate,
const string& filename) {
fstream stream(filename.c_str(), fstream::out);
// save 2D & 3D poses
2014-11-02 02:23:07 +08:00
Values::ConstFiltered<Pose2> viewPose2 = estimate.filter<Pose2>();
BOOST_FOREACH(const Values::ConstFiltered<Pose2>::KeyValuePair& key_value, viewPose2) {
stream << "VERTEX_SE2 " << key_value.key << " " << key_value.value.x() << " "
<< key_value.value.y() << " " << key_value.value.theta() << endl;
}
2014-11-02 02:23:07 +08:00
Values::ConstFiltered<Pose3> viewPose3 = estimate.filter<Pose3>();
BOOST_FOREACH(const Values::ConstFiltered<Pose3>::KeyValuePair& key_value, viewPose3) {
Point3 p = key_value.value.translation();
Rot3 R = key_value.value.rotation();
stream << "VERTEX_SE3:QUAT " << key_value.key << " " << p.x() << " " << p.y() << " " << p.z()
<< " " << R.toQuaternion().x() << " " << R.toQuaternion().y() << " " << R.toQuaternion().z()
<< " " << R.toQuaternion().w() << endl;
}
// save edges (2D or 3D)
BOOST_FOREACH(boost::shared_ptr<NonlinearFactor> factor_, graph) {
boost::shared_ptr<BetweenFactor<Pose2> > factor =
boost::dynamic_pointer_cast<BetweenFactor<Pose2> >(factor_);
if (factor){
SharedNoiseModel model = factor->noiseModel();
boost::shared_ptr<noiseModel::Gaussian> gaussianModel =
boost::dynamic_pointer_cast<noiseModel::Gaussian>(model);
if (!gaussianModel){
model->print("model\n");
throw invalid_argument("writeG2o: invalid noise model!");
}
Matrix Info = gaussianModel->R().transpose() * gaussianModel->R();
Pose2 pose = factor->measured(); //.inverse();
stream << "EDGE_SE2 " << factor->key1() << " " << factor->key2() << " "
<< pose.x() << " " << pose.y() << " " << pose.theta();
for (int i = 0; i < 3; i++){
for (int j = i; j < 3; j++){
stream << " " << Info(i, j);
}
}
stream << endl;
}
boost::shared_ptr< BetweenFactor<Pose3> > factor3D =
boost::dynamic_pointer_cast< BetweenFactor<Pose3> >(factor_);
if (factor3D){
SharedNoiseModel model = factor3D->noiseModel();
boost::shared_ptr<noiseModel::Gaussian> gaussianModel =
boost::dynamic_pointer_cast<noiseModel::Gaussian>(model);
if (!gaussianModel){
model->print("model\n");
throw invalid_argument("writeG2o: invalid noise model!");
}
Matrix Info = gaussianModel->R().transpose() * gaussianModel->R();
Pose3 pose3D = factor3D->measured();
Point3 p = pose3D.translation();
Rot3 R = pose3D.rotation();
stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2() << " "
<< p.x() << " " << p.y() << " " << p.z() << " " << R.toQuaternion().x()
<< " " << R.toQuaternion().y() << " " << R.toQuaternion().z() << " " << R.toQuaternion().w();
Matrix InfoG2o = eye(6);
InfoG2o.block(0,0,3,3) = Info.block(3,3,3,3); // cov translation
InfoG2o.block(3,3,3,3) = Info.block(0,0,3,3); // cov rotation
InfoG2o.block(0,3,3,3) = Info.block(0,3,3,3); // off diagonal
InfoG2o.block(3,0,3,3) = Info.block(3,0,3,3); // off diagonal
for (int i = 0; i < 6; i++){
for (int j = i; j < 6; j++){
stream << " " << InfoG2o(i, j);
}
}
stream << endl;
}
}
stream.close();
}
/* ************************************************************************* */
GraphAndValues load3D(const string& filename) {
ifstream is(filename.c_str());
if (!is)
2014-08-22 22:40:16 +08:00
throw invalid_argument("load3D: can not find file " + filename);
Values::shared_ptr initial(new Values);
NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph);
2014-08-22 22:40:16 +08:00
while (!is.eof()) {
char buf[LINESIZE];
is.getline(buf, LINESIZE);
istringstream ls(buf);
string tag;
ls >> tag;
if (tag == "VERTEX3") {
2014-08-26 04:36:58 +08:00
Key id;
double x, y, z, roll, pitch, yaw;
ls >> id >> x >> y >> z >> roll >> pitch >> yaw;
2016-01-27 15:09:58 +08:00
Rot3 R = Rot3::Ypr(yaw,pitch,roll);
Point3 t = Point3(x, y, z);
initial->insert(id, Pose3(R,t));
}
if (tag == "VERTEX_SE3:QUAT") {
2014-08-26 04:36:58 +08:00
Key id;
double x, y, z, qx, qy, qz, qw;
ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw;
2016-01-27 15:57:34 +08:00
Rot3 R = Rot3::Quaternion(qw, qx, qy, qz);
Point3 t = Point3(x, y, z);
initial->insert(id, Pose3(R,t));
}
}
is.clear(); /* clears the end-of-file and error flags */
is.seekg(0, ios::beg);
2014-08-22 22:40:16 +08:00
while (!is.eof()) {
char buf[LINESIZE];
is.getline(buf, LINESIZE);
istringstream ls(buf);
string tag;
ls >> tag;
if (tag == "EDGE3") {
2014-08-26 04:36:58 +08:00
Key id1, id2;
double x, y, z, roll, pitch, yaw;
ls >> id1 >> id2 >> x >> y >> z >> roll >> pitch >> yaw;
2016-01-27 15:09:58 +08:00
Rot3 R = Rot3::Ypr(yaw,pitch,roll);
Point3 t = Point3(x, y, z);
Matrix m = eye(6);
for (int i = 0; i < 6; i++)
for (int j = i; j < 6; j++)
ls >> m(i, j);
SharedNoiseModel model = noiseModel::Gaussian::Information(m);
NonlinearFactor::shared_ptr factor(
new BetweenFactor<Pose3>(id1, id2, Pose3(R,t), model));
graph->push_back(factor);
}
if (tag == "EDGE_SE3:QUAT") {
Matrix m = eye(6);
2014-08-26 04:36:58 +08:00
Key id1, id2;
double x, y, z, qx, qy, qz, qw;
ls >> id1 >> id2 >> x >> y >> z >> qx >> qy >> qz >> qw;
2016-01-27 15:57:34 +08:00
Rot3 R = Rot3::Quaternion(qw, qx, qy, qz);
Point3 t = Point3(x, y, z);
for (int i = 0; i < 6; i++){
for (int j = i; j < 6; j++){
double mij;
ls >> mij;
m(i, j) = mij;
m(j, i) = mij;
}
}
Matrix mgtsam = eye(6);
mgtsam.block(0,0,3,3) = m.block(3,3,3,3); // cov rotation
mgtsam.block(3,3,3,3) = m.block(0,0,3,3); // cov translation
mgtsam.block(0,3,3,3) = m.block(0,3,3,3); // off diagonal
mgtsam.block(3,0,3,3) = m.block(3,0,3,3); // off diagonal
SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam);
NonlinearFactor::shared_ptr factor(new BetweenFactor<Pose3>(id1, id2, Pose3(R,t), model));
graph->push_back(factor);
}
}
return make_pair(graph, initial);
2010-01-23 04:18:40 +08:00
}
/* ************************************************************************* */
2014-06-01 06:08:02 +08:00
Rot3 openGLFixedRotation() { // this is due to different convention for cameras in gtsam and openGL
/* R = [ 1 0 0
* 0 -1 0
* 0 0 -1]
*/
2014-06-01 06:08:02 +08:00
Matrix3 R_mat = Matrix3::Zero(3, 3);
R_mat(0, 0) = 1.0;
R_mat(1, 1) = -1.0;
R_mat(2, 2) = -1.0;
return Rot3(R_mat);
}
/* ************************************************************************* */
2014-06-01 06:08:02 +08:00
Pose3 openGL2gtsam(const Rot3& R, double tx, double ty, double tz) {
Rot3 R90 = openGLFixedRotation();
2014-06-01 06:08:02 +08:00
Rot3 wRc = (R.inverse()).compose(R90);
// Our camera-to-world translation wTc = -R'*t
2014-06-01 06:08:02 +08:00
return Pose3(wRc, R.unrotate(Point3(-tx, -ty, -tz)));
}
/* ************************************************************************* */
2014-06-01 06:08:02 +08:00
Pose3 gtsam2openGL(const Rot3& R, double tx, double ty, double tz) {
Rot3 R90 = openGLFixedRotation();
2014-06-01 06:08:02 +08:00
Rot3 cRw_openGL = R90.compose(R.inverse());
Point3 t_openGL = cRw_openGL.rotate(Point3(-tx, -ty, -tz));
return Pose3(cRw_openGL, t_openGL);
}
/* ************************************************************************* */
2014-06-01 06:08:02 +08:00
Pose3 gtsam2openGL(const Pose3& PoseGTSAM) {
return gtsam2openGL(PoseGTSAM.rotation(), PoseGTSAM.x(), PoseGTSAM.y(),
PoseGTSAM.z());
}
/* ************************************************************************* */
2014-06-01 06:08:02 +08:00
bool readBundler(const string& filename, SfM_data &data) {
// Load the data file
2014-06-01 06:08:02 +08:00
ifstream is(filename.c_str(), ifstream::in);
if (!is) {
cout << "Error in readBundler: can not find the file!!" << endl;
return false;
}
// Ignore the first line
char aux[500];
2014-06-01 06:08:02 +08:00
is.getline(aux, 500);
// Get the number of camera poses and 3D points
size_t nrPoses, nrPoints;
is >> nrPoses >> nrPoints;
// Get the information for the camera poses
2014-06-01 06:08:02 +08:00
for (size_t i = 0; i < nrPoses; i++) {
// Get the focal length and the radial distortion parameters
float f, k1, k2;
is >> f >> k1 >> k2;
Cal3Bundler K(f, k1, k2);
// Get the rotation matrix
float r11, r12, r13;
float r21, r22, r23;
float r31, r32, r33;
2014-06-01 06:08:02 +08:00
is >> r11 >> r12 >> r13 >> r21 >> r22 >> r23 >> r31 >> r32 >> r33;
// Bundler-OpenGL rotation matrix
2014-06-01 06:08:02 +08:00
Rot3 R(r11, r12, r13, r21, r22, r23, r31, r32, r33);
// Check for all-zero R, in which case quit
2014-06-01 06:08:02 +08:00
if (r11 == 0 && r12 == 0 && r13 == 0) {
cout << "Error in readBundler: zero rotation matrix for pose " << i
<< endl;
return false;
}
// Get the translation vector
float tx, ty, tz;
is >> tx >> ty >> tz;
2014-06-01 06:08:02 +08:00
Pose3 pose = openGL2gtsam(R, tx, ty, tz);
2016-02-26 08:52:41 +08:00
data.cameras.emplace_back(pose, K);
}
// Get the information for the 3D points
2016-02-26 08:52:41 +08:00
data.tracks.reserve(nrPoints);
2014-06-01 06:08:02 +08:00
for (size_t j = 0; j < nrPoints; j++) {
SfM_Track track;
// Get the 3D position
float x, y, z;
is >> x >> y >> z;
2014-06-01 06:08:02 +08:00
track.p = Point3(x, y, z);
// Get the color information
float r, g, b;
is >> r >> g >> b;
2014-06-01 06:08:02 +08:00
track.r = r / 255.f;
track.g = g / 255.f;
track.b = b / 255.f;
// Now get the visibility information
size_t nvisible = 0;
is >> nvisible;
2016-02-26 08:52:41 +08:00
track.measurements.reserve(nvisible);
track.siftIndices.reserve(nvisible);
2014-06-01 06:08:02 +08:00
for (size_t k = 0; k < nvisible; k++) {
size_t cam_idx = 0, point_idx = 0;
float u, v;
is >> cam_idx >> point_idx >> u >> v;
2016-02-26 08:52:41 +08:00
track.measurements.emplace_back(cam_idx, Point2(u, -v));
track.siftIndices.emplace_back(cam_idx, point_idx);
}
data.tracks.push_back(track);
}
is.close();
return true;
}
/* ************************************************************************* */
2014-06-01 06:08:02 +08:00
bool readBAL(const string& filename, SfM_data &data) {
// Load the data file
2014-06-01 06:08:02 +08:00
ifstream is(filename.c_str(), ifstream::in);
if (!is) {
cout << "Error in readBAL: can not find the file!!" << endl;
return false;
}
// Get the number of camera poses and 3D points
size_t nrPoses, nrPoints, nrObservations;
is >> nrPoses >> nrPoints >> nrObservations;
data.tracks.resize(nrPoints);
// Get the information for the observations
2014-06-01 06:08:02 +08:00
for (size_t k = 0; k < nrObservations; k++) {
size_t i = 0, j = 0;
float u, v;
is >> i >> j >> u >> v;
2016-02-26 08:52:41 +08:00
data.tracks[j].emplace_back(i, Point2(u, -v));
}
// Get the information for the camera poses
2014-06-01 06:08:02 +08:00
for (size_t i = 0; i < nrPoses; i++) {
2015-07-06 07:11:04 +08:00
// Get the Rodrigues vector
float wx, wy, wz;
is >> wx >> wy >> wz;
2015-07-06 07:11:04 +08:00
Rot3 R = Rot3::Rodrigues(wx, wy, wz); // BAL-OpenGL rotation matrix
// Get the translation vector
float tx, ty, tz;
is >> tx >> ty >> tz;
2014-06-01 06:08:02 +08:00
Pose3 pose = openGL2gtsam(R, tx, ty, tz);
// Get the focal length and the radial distortion parameters
float f, k1, k2;
is >> f >> k1 >> k2;
Cal3Bundler K(f, k1, k2);
2016-02-26 08:52:41 +08:00
data.cameras.emplace_back(pose, K);
}
// Get the information for the 3D points
2014-06-01 06:08:02 +08:00
for (size_t j = 0; j < nrPoints; j++) {
// Get the 3D position
float x, y, z;
is >> x >> y >> z;
SfM_Track& track = data.tracks[j];
2014-06-01 06:08:02 +08:00
track.p = Point3(x, y, z);
2013-11-19 22:04:52 +08:00
track.r = 0.4f;
track.g = 0.4f;
track.b = 0.4f;
}
is.close();
return true;
}
/* ************************************************************************* */
2014-06-01 06:08:02 +08:00
bool writeBAL(const string& filename, SfM_data &data) {
// Open the output file
ofstream os;
os.open(filename.c_str());
os.precision(20);
if (!os.is_open()) {
cout << "Error in writeBAL: can not open the file!!" << endl;
return false;
}
// Write the number of camera poses and 3D points
2014-06-01 06:08:02 +08:00
size_t nrObservations = 0;
for (size_t j = 0; j < data.number_tracks(); j++) {
nrObservations += data.tracks[j].number_measurements();
}
// Write observations
2014-06-01 06:08:02 +08:00
os << data.number_cameras() << " " << data.number_tracks() << " "
<< nrObservations << endl;
os << endl;
2014-06-01 06:08:02 +08:00
for (size_t j = 0; j < data.number_tracks(); j++) { // for each 3D point j
const SfM_Track& track = data.tracks[j];
2014-06-01 06:08:02 +08:00
for (size_t k = 0; k < track.number_measurements(); k++) { // for each observation of the 3D point j
2013-11-19 22:04:52 +08:00
size_t i = track.measurements[k].first; // camera id
double u0 = data.cameras[i].calibration().u0();
double v0 = data.cameras[i].calibration().v0();
2014-06-01 06:08:02 +08:00
if (u0 != 0 || v0 != 0) {
cout
<< "writeBAL has not been tested for calibration with nonzero (u0,v0)"
<< endl;
}
double pixelBALx = track.measurements[k].second.x() - u0; // center of image is the origin
2014-06-01 06:08:02 +08:00
double pixelBALy = -(track.measurements[k].second.y() - v0); // center of image is the origin
Point2 pixelMeasurement(pixelBALx, pixelBALy);
2014-06-01 06:08:02 +08:00
os << i /*camera id*/<< " " << j /*point id*/<< " "
<< pixelMeasurement.x() /*u of the pixel*/<< " "
<< pixelMeasurement.y() /*v of the pixel*/<< endl;
}
}
os << endl;
// Write cameras
2014-06-01 06:08:02 +08:00
for (size_t i = 0; i < data.number_cameras(); i++) { // for each camera
Pose3 poseGTSAM = data.cameras[i].pose();
Cal3Bundler cameraCalibration = data.cameras[i].calibration();
Pose3 poseOpenGL = gtsam2openGL(poseGTSAM);
2014-06-01 06:08:02 +08:00
os << Rot3::Logmap(poseOpenGL.rotation()) << endl;
os << poseOpenGL.translation().x() << endl;
os << poseOpenGL.translation().y() << endl;
os << poseOpenGL.translation().z() << endl;
2014-06-01 06:08:02 +08:00
os << cameraCalibration.fx() << endl;
os << cameraCalibration.k1() << endl;
os << cameraCalibration.k2() << endl;
os << endl;
}
// Write the points
2014-06-01 06:08:02 +08:00
for (size_t j = 0; j < data.number_tracks(); j++) { // for each 3D point j
Point3 point = data.tracks[j].p;
os << point.x() << endl;
os << point.y() << endl;
os << point.z() << endl;
os << endl;
}
os.close();
return true;
}
2014-06-01 06:08:02 +08:00
bool writeBALfromValues(const string& filename, const SfM_data &data,
Values& values) {
2014-03-13 13:36:38 +08:00
SfM_data dataValues = data;
// Store poses or cameras in SfM_data
Values valuesPoses = values.filter<Pose3>();
2014-06-01 06:08:02 +08:00
if (valuesPoses.size() == dataValues.number_cameras()) { // we only estimated camera poses
for (size_t i = 0; i < dataValues.number_cameras(); i++) { // for each camera
Key poseKey = symbol('x', i);
Pose3 pose = values.at<Pose3>(poseKey);
2014-03-13 13:36:38 +08:00
Cal3Bundler K = dataValues.cameras[i].calibration();
PinholeCamera<Cal3Bundler> camera(pose, K);
2014-03-13 13:36:38 +08:00
dataValues.cameras[i] = camera;
}
} else {
2014-06-01 06:08:02 +08:00
Values valuesCameras = values.filter<PinholeCamera<Cal3Bundler> >();
if (valuesCameras.size() == dataValues.number_cameras()) { // we only estimated camera poses and calibration
for (size_t i = 0; i < dataValues.number_cameras(); i++) { // for each camera
2014-03-05 04:06:32 +08:00
Key cameraKey = i; // symbol('c',i);
2014-06-01 06:08:02 +08:00
PinholeCamera<Cal3Bundler> camera =
values.at<PinholeCamera<Cal3Bundler> >(cameraKey);
2014-03-13 13:36:38 +08:00
dataValues.cameras[i] = camera;
}
2014-06-01 06:08:02 +08:00
} else {
cout
<< "writeBALfromValues: different number of cameras in SfM_dataValues (#cameras= "
<< dataValues.number_cameras() << ") and values (#cameras "
<< valuesPoses.size() << ", #poses " << valuesCameras.size() << ")!!"
<< endl;
return false;
}
}
// Store 3D points in SfM_data
Values valuesPoints = values.filter<Point3>();
2014-06-01 06:08:02 +08:00
if (valuesPoints.size() != dataValues.number_tracks()) {
cout
<< "writeBALfromValues: different number of points in SfM_dataValues (#points= "
<< dataValues.number_tracks() << ") and values (#points "
<< valuesPoints.size() << ")!!" << endl;
}
2014-06-01 06:08:02 +08:00
for (size_t j = 0; j < dataValues.number_tracks(); j++) { // for each point
2014-04-29 01:16:25 +08:00
Key pointKey = P(j);
2014-06-01 06:08:02 +08:00
if (values.exists(pointKey)) {
Point3 point = values.at<Point3>(pointKey);
2014-03-13 13:36:38 +08:00
dataValues.tracks[j].p = point;
2014-06-01 06:08:02 +08:00
} else {
2014-03-13 13:36:38 +08:00
dataValues.tracks[j].r = 1.0;
dataValues.tracks[j].g = 0.0;
dataValues.tracks[j].b = 0.0;
dataValues.tracks[j].p = Point3(0,0,0);
}
}
// Write SfM_data to file
2014-03-13 13:36:38 +08:00
return writeBAL(filename, dataValues);
}
Values initialCamerasEstimate(const SfM_data& db) {
Values initial;
size_t i = 0; // NO POINTS: j = 0;
BOOST_FOREACH(const SfM_Camera& camera, db.cameras)
2014-06-01 06:08:02 +08:00
initial.insert(i++, camera);
return initial;
}
Values initialCamerasAndPointsEstimate(const SfM_data& db) {
Values initial;
size_t i = 0, j = 0;
BOOST_FOREACH(const SfM_Camera& camera, db.cameras)
2014-06-01 06:08:02 +08:00
initial.insert((i++), camera);
BOOST_FOREACH(const SfM_Track& track, db.tracks)
2014-06-01 06:08:02 +08:00
initial.insert(P(j++), track.p);
return initial;
}
} // \namespace gtsam