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
8 changes: 8 additions & 0 deletions gtsam/gtsam.i
Original file line number Diff line number Diff line change
Expand Up @@ -2759,21 +2759,29 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
};

#include <gtsam/slam/dataset.h>

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

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(const gtsam::SfmTrack& t) ;
void add_camera(const 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
21 changes: 21 additions & 0 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 @@ -221,10 +222,16 @@ struct SfmTrack {
float r, g, b; ///< RGB color of the 3D point
std::vector<SfmMeasurement> measurements; ///< The 2D image projections (id,(u,v))
std::vector<SiftIndex> siftIndices;

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

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


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


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

Expand All @@ -260,6 +273,14 @@ struct SfmData {
SfmTrack track(size_t idx) const {
return tracks[idx];
}

void add_track(const SfmTrack& t) {
tracks.push_back(t);
}

void add_camera(const SfmCamera& cam){
cameras.push_back(cam);
}
};

/**
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
2 changes: 2 additions & 0 deletions python/gtsam/preamble.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,3 +10,5 @@ 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>);
2 changes: 2 additions & 0 deletions python/gtsam/specializations.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,3 +13,5 @@ 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");
swarrier246 marked this conversation as resolved.
Show resolved Hide resolved
//py::bind_vector<std::vector<gtsam::SiftIndex> >(m_, "SiftIndexVector");
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()