Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/wrap sfm data #569

Merged
merged 12 commits into from
Nov 9, 2020
2 changes: 1 addition & 1 deletion examples/CreateSFMExampleData.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void createExampleBALFile(const string& filename, const vector<Point3>& P,

// Project points in both cameras
for (size_t i = 0; i < 2; i++)
track.measurements.push_back(make_pair(i, data.cameras[i].project(p)));
track.Measurements.push_back(make_pair(i, data.cameras[i].project(p)));

// Add track to data
data.tracks.push_back(track);
Expand Down
2 changes: 1 addition & 1 deletion examples/SFMExampleExpressions_bal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ int main(int argc, char* argv[]) {
for (const SfmTrack& track : mydata.tracks) {
// Leaf expression for j^th point
Point3_ point_('p', j);
for (const SfmMeasurement& m : track.measurements) {
for (const SfmMeasurement& m : track.Measurements) {
size_t i = m.first;
Point2 uv = m.second;
// Leaf expression for i^th camera
Expand Down
2 changes: 1 addition & 1 deletion examples/SFMExample_bal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ int main (int argc, char* argv[]) {
// Add measurements to the factor graph
size_t j = 0;
for(const SfmTrack& track: mydata.tracks) {
for(const SfmMeasurement& m: track.measurements) {
for(const SfmMeasurement& m: track.Measurements) {
size_t i = m.first;
Point2 uv = m.second;
graph.emplace_shared<MyFactor>(uv, noise, C(i), P(j)); // note use of shorthand symbols C and P
Expand Down
2 changes: 1 addition & 1 deletion examples/SFMExample_bal_COLAMD_METIS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ int main(int argc, char* argv[]) {
// Add measurements to the factor graph
size_t j = 0;
for (const SfmTrack& track : mydata.tracks) {
for (const SfmMeasurement& m : track.measurements) {
for (const SfmMeasurement& m : track.Measurements) {
size_t i = m.first;
Point2 uv = m.second;
graph.emplace_shared<MyFactor>(
Expand Down
18 changes: 16 additions & 2 deletions gtsam/gtsam.i
Original file line number Diff line number Diff line change
Expand Up @@ -2759,21 +2759,35 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
};

#include <gtsam/slam/dataset.h>
// Dummy classes, for MATLAB wrappers
class SfmMeasurement{};
class SiftIndex{ };
class SfmMeasurements{};
class SfmCamera{};
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved

class SfmTrack {
SfmTrack();
Point3 point3() const;
size_t number_measurements() const;
pair<size_t, gtsam::Point2> measurement(size_t idx) const;
pair<size_t, size_t> siftIndex(size_t idx) const;
void setP(gtsam::Point3& p_);
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
gtsam::SfmMeasurement measurement(size_t idx) const;
gtsam::SiftIndex siftIndex(size_t idx) const;
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
void add_measurement(pair<size_t, gtsam::Point2> m);
SfmMeasurements& measurements();
};

class SfmData {
SfmData();
size_t number_cameras() const;
size_t number_tracks() const;
gtsam::PinholeCamera<gtsam::Cal3Bundler> camera(size_t idx) const;
gtsam::SfmTrack track(size_t idx) const;
void add_track(gtsam::SfmTrack t);
void add_camera(gtsam::SfmCamera cam);
};

gtsam::SfmData readBal(string filename);
bool writeBAL(string filename, gtsam::SfmData& data);
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
gtsam::Values initialCamerasEstimate(const gtsam::SfmData& db);
gtsam::Values initialCamerasAndPointsEstimate(const gtsam::SfmData& db);

Expand Down
4 changes: 2 additions & 2 deletions gtsam/slam/SmartFactorBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -144,8 +144,8 @@ class SmartFactorBase: public NonlinearFactor {
template<class SFM_TRACK>
void add(const SFM_TRACK& trackToAdd) {
for (size_t k = 0; k < trackToAdd.number_measurements(); k++) {
this->measured_.push_back(trackToAdd.measurements[k].second);
this->keys_.push_back(trackToAdd.measurements[k].first);
this->measured_.push_back(trackToAdd.Measurements[k].second);
this->keys_.push_back(trackToAdd.Measurements[k].first);
}
}

Expand Down
12 changes: 6 additions & 6 deletions gtsam/slam/dataset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1052,13 +1052,13 @@ bool readBundler(const string &filename, SfmData &data) {
size_t nvisible = 0;
is >> nvisible;

track.measurements.reserve(nvisible);
track.Measurements.reserve(nvisible);
track.siftIndices.reserve(nvisible);
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;
track.measurements.emplace_back(cam_idx, Point2(u, -v));
track.Measurements.emplace_back(cam_idx, Point2(u, -v));
track.siftIndices.emplace_back(cam_idx, point_idx);
}

Expand Down Expand Up @@ -1089,7 +1089,7 @@ bool readBAL(const string &filename, SfmData &data) {
size_t i = 0, j = 0;
float u, v;
is >> i >> j >> u >> v;
data.tracks[j].measurements.emplace_back(i, Point2(u, -v));
data.tracks[j].Measurements.emplace_back(i, Point2(u, -v));
}

// Get the information for the camera poses
Expand Down Expand Up @@ -1163,7 +1163,7 @@ bool writeBAL(const string &filename, SfmData &data) {

for (size_t k = 0; k < track.number_measurements();
k++) { // for each observation of the 3D point j
size_t i = track.measurements[k].first; // camera id
size_t i = track.Measurements[k].first; // camera id
double u0 = data.cameras[i].calibration().u0();
double v0 = data.cameras[i].calibration().v0();

Expand All @@ -1173,9 +1173,9 @@ bool writeBAL(const string &filename, SfmData &data) {
<< endl;
}

double pixelBALx = track.measurements[k].second.x() -
double pixelBALx = track.Measurements[k].second.x() -
u0; // center of image is the origin
double pixelBALy = -(track.measurements[k].second.y() -
double pixelBALy = -(track.Measurements[k].second.y() -
v0); // center of image is the origin
Point2 pixelMeasurement(pixelBALx, pixelBALy);
os << i /*camera id*/ << " " << j /*point id*/ << " "
Expand Down
31 changes: 28 additions & 3 deletions gtsam/slam/dataset.h
Original file line number Diff line number Diff line change
Expand Up @@ -210,6 +210,7 @@ GTSAM_EXPORT GraphAndValues load3D(const std::string& filename);

/// A measurement with its camera index
typedef std::pair<size_t, Point2> SfmMeasurement;
typedef std::vector<SfmMeasurement> SfmMeasurements;
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved

/// SfmTrack
typedef std::pair<size_t, size_t> SiftIndex;
Expand All @@ -219,15 +220,21 @@ struct SfmTrack {
SfmTrack(): p(0,0,0) {}
Point3 p; ///< 3D position of the point
float r, g, b; ///< RGB color of the 3D point
std::vector<SfmMeasurement> measurements; ///< The 2D image projections (id,(u,v))
std::vector<SfmMeasurement> Measurements; ///< The 2D image projections (id,(u,v))
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
std::vector<SiftIndex> siftIndices;

/// Total number of measurements in this track
size_t number_measurements() const {
return measurements.size();
return Measurements.size();
}
/// Set 3D point
void setP(Point3& p_){
p = p_;
}

/// Get the measurement (camera index, Point2) at pose index `idx`
SfmMeasurement measurement(size_t idx) const {
return measurements[idx];
return Measurements[idx];
}
/// Get the SIFT feature index corresponding to the measurement at `idx`
SiftIndex siftIndex(size_t idx) const {
Expand All @@ -236,13 +243,23 @@ struct SfmTrack {
Point3 point3() const {
return p;
}
void add_measurement(pair<size_t, gtsam::Point2> m) {
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
Measurements.push_back(m);
}

SfmMeasurements& measurements() {
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
return Measurements;
}

swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
};


/// Define the structure for the camera poses
typedef PinholeCamera<Cal3Bundler> SfmCamera;

/// Define the structure for SfM data
struct SfmData {
std::vector<SfmMeasurement> Measurements;
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
std::vector<SfmCamera> cameras; ///< Set of cameras
std::vector<SfmTrack> tracks; ///< Sparse set of points
size_t number_cameras() const {
Expand All @@ -260,6 +277,14 @@ struct SfmData {
SfmTrack track(size_t idx) const {
return tracks[idx];
}

void add_track(SfmTrack t) {
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
tracks.push_back(t);
}

void add_camera(SfmCamera cam){
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
cameras.push_back(cam);
}
};

/**
Expand Down
16 changes: 8 additions & 8 deletions gtsam/slam/tests/testDataset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,9 +166,9 @@ TEST( dataSet, Balbianello)
EXPECT_LONGS_EQUAL(3,track0.number_measurements());

// Check projection of a given point
EXPECT_LONGS_EQUAL(0,track0.measurements[0].first);
EXPECT_LONGS_EQUAL(0,track0.Measurements[0].first);
const SfmCamera& camera0 = mydata.cameras[0];
Point2 expected = camera0.project(track0.p), actual = track0.measurements[0].second;
Point2 expected = camera0.project(track0.p), actual = track0.Measurements[0].second;
EXPECT(assert_equal(expected,actual,1));
}

Expand Down Expand Up @@ -476,9 +476,9 @@ TEST( dataSet, readBAL_Dubrovnik)
EXPECT_LONGS_EQUAL(3,track0.number_measurements());

// Check projection of a given point
EXPECT_LONGS_EQUAL(0,track0.measurements[0].first);
EXPECT_LONGS_EQUAL(0,track0.Measurements[0].first);
const SfmCamera& camera0 = mydata.cameras[0];
Point2 expected = camera0.project(track0.p), actual = track0.measurements[0].second;
Point2 expected = camera0.project(track0.p), actual = track0.Measurements[0].second;
EXPECT(assert_equal(expected,actual,12));
}

Expand Down Expand Up @@ -557,8 +557,8 @@ TEST( dataSet, writeBAL_Dubrovnik)

// check measurements
for (size_t k = 0; k < actualTrack.number_measurements(); k++){
EXPECT_LONGS_EQUAL(expectedTrack.measurements[k].first,actualTrack.measurements[k].first);
EXPECT(assert_equal(expectedTrack.measurements[k].second,actualTrack.measurements[k].second));
EXPECT_LONGS_EQUAL(expectedTrack.Measurements[k].first,actualTrack.Measurements[k].first);
EXPECT(assert_equal(expectedTrack.Measurements[k].second,actualTrack.Measurements[k].second));
}
}
}
Expand Down Expand Up @@ -600,9 +600,9 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){
EXPECT_LONGS_EQUAL(3,track0.number_measurements());

// Check projection of a given point
EXPECT_LONGS_EQUAL(0,track0.measurements[0].first);
EXPECT_LONGS_EQUAL(0,track0.Measurements[0].first);
const SfmCamera& camera0 = writtenData.cameras[0];
Point2 expected = camera0.project(track0.p), actual = track0.measurements[0].second;
Point2 expected = camera0.project(track0.p), actual = track0.Measurements[0].second;
EXPECT(assert_equal(expected,actual,12));

Pose3 expectedPose = camera0.pose();
Expand Down
8 changes: 4 additions & 4 deletions gtsam/slam/tests/testEssentialMatrixFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@ EssentialMatrix trueE(trueRotation, trueDirection);
double baseline = 0.1; // actual baseline of the camera

Point2 pA(size_t i) {
return data.tracks[i].measurements[0].second;
return data.tracks[i].Measurements[0].second;
}
Point2 pB(size_t i) {
return data.tracks[i].measurements[1].second;
return data.tracks[i].Measurements[1].second;
}
Vector vA(size_t i) {
return EssentialMatrix::Homogeneous(pA(i));
Expand Down Expand Up @@ -367,10 +367,10 @@ EssentialMatrix trueE(aRb, Unit3(aTb));
double baseline = 10; // actual baseline of the camera

Point2 pA(size_t i) {
return data.tracks[i].measurements[0].second;
return data.tracks[i].Measurements[0].second;
}
Point2 pB(size_t i) {
return data.tracks[i].measurements[1].second;
return data.tracks[i].Measurements[1].second;
}

boost::shared_ptr<Cal3Bundler> //
Expand Down
4 changes: 2 additions & 2 deletions gtsam/slam/tests/testSmartProjectionFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -283,14 +283,14 @@ TEST(SmartProjectionFactor, perturbPoseAndOptimizeFromSfM_tracks ) {

SfmTrack track1;
for (size_t i = 0; i < 3; ++i) {
track1.measurements.emplace_back(i + 1, measurements_cam1.at(i));
track1.Measurements.emplace_back(i + 1, measurements_cam1.at(i));
}
SmartFactor::shared_ptr smartFactor1(new SmartFactor(unit2));
smartFactor1->add(track1);

SfmTrack track2;
for (size_t i = 0; i < 3; ++i) {
track2.measurements.emplace_back(i + 1, measurements_cam2.at(i));
track2.Measurements.emplace_back(i + 1, measurements_cam2.at(i));
}
SmartFactor::shared_ptr smartFactor2(new SmartFactor(unit2));
smartFactor2->add(track2);
Expand Down
3 changes: 3 additions & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,9 @@ set(ignore
gtsam::BetweenFactorPose3s
gtsam::Point2Vector
gtsam::Pose3Vector
gtsam::SfmMeasurement
gtsam::SfmCamera
gtsam::SiftIndex
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
gtsam::KeyVector
gtsam::BinaryMeasurementsUnit3
gtsam::KeyPairDoubleMap)
Expand Down
3 changes: 3 additions & 0 deletions python/gtsam/preamble.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,3 +10,6 @@ PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Pose3>);
PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > >);
PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > >);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::IndexPair>);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SfmMeasurement>);
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SiftIndex>);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SfmCamera>);
3 changes: 3 additions & 0 deletions python/gtsam/specializations.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,3 +13,6 @@ py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(m_, "Bina
py::bind_map<gtsam::IndexPairSetMap>(m_, "IndexPairSetMap");
py::bind_vector<gtsam::IndexPairVector>(m_, "IndexPairVector");
py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap");
py::bind_vector<std::vector<gtsam::SfmMeasurement> >(m_, "Measurement");
py::bind_vector<std::vector<gtsam::SiftIndex> >(m_, "SiftIndexVector");
py::bind_vector<std::vector<gtsam::SfmCamera> >(m_, "cameras");
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
79 changes: 79 additions & 0 deletions python/gtsam/tests/test_SfmData.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved

See LICENSE for the license information

Unit tests for testing dataset access.
Author: Frank Dellaert (Python: Sushmita Warrier)
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
"""
# pylint: disable=invalid-name, no-name-in-module, no-member

from __future__ import print_function

import unittest

import numpy as np

import gtsam
#from gtsam import SfmCamera
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
from gtsam.utils.test_case import GtsamTestCase
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved


class TestSfmData(GtsamTestCase):
"""Tests for SfmData and SfmTrack modules."""

def setUp(self):
"""Initialize SfmData and SfmTrack"""
self.data = gtsam.SfmData()
self.tracks = gtsam.SfmTrack()

def test_tracks(self):
"""Test functions in SfmTrack"""
# measurement is of format (camera_idx, imgPoint)
# create camera indices for two cameras
i1, i2 = np.random.randint(5), np.random.randint(5)
akshay-krishnan marked this conversation as resolved.
Show resolved Hide resolved
# create imgPoint for cameras i1 and i2
uv_i1 = gtsam.Point2(np.random.randint(5), np.random.randint(5))
uv_i2 = gtsam.Point2(np.random.randint(5), np.random.randint(5))
m_i1 = (i1, uv_i1)
m_i2 = (i2, uv_i2)
# add measurements to the track
self.tracks.add_measurement(m_i1)
self.tracks.add_measurement(m_i2)
# Number of measurements in the track is 2
self.assertEqual(self.tracks.number_measurements(), 2)
# camera_idx in the first measurement of the track corresponds to i1
self.assertEqual(self.tracks.measurement(0)[0], i1)
# Set arbitrary 3D point corresponding to the track
self.tracks.setP(gtsam.Point3(2.5, 3.3, 1.2))
np.testing.assert_array_almost_equal(
gtsam.Point3(2.5,3.3,1.2),
self.tracks.point3()
)


def test_data(self):
"""Test functions in SfmData"""
#cam1 = gtsam.SfmCamera(1500, 1200, 0, 640, 480)
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
# Create new track with 3 measurements
track2 = gtsam.SfmTrack()
i1, i2, i3 = np.random.randint(5), np.random.randint(5), np.random.randint(5)
uv_i1 = gtsam.Point2(np.random.randint(5), np.random.randint(5))
akshay-krishnan marked this conversation as resolved.
Show resolved Hide resolved
uv_i2 = gtsam.Point2(np.random.randint(5), np.random.randint(5))
uv_i3 = gtsam.Point2(np.random.randint(5), np.random.randint(5))
m_i1, m_i2, m_i3 = (i1, uv_i1), (i2, uv_i2), (i3, uv_i3)
# add measurements to the track
track2.add_measurement(m_i1)
track2.add_measurement(m_i2)
track2.add_measurement(m_i3)
self.data.add_track(self.tracks)
self.data.add_track(track2)
# Number of tracks in SfmData is 2
self.assertEqual(self.data.number_tracks(), 2)
# camera idx of first measurement of second track corresponds to i1
self.assertEqual(self.data.track(1).measurement(0)[0], i1)
johnwlambert marked this conversation as resolved.
Show resolved Hide resolved

if __name__ == '__main__':
unittest.main()
Loading