fix all wrapper issues
parent
2434d3a41e
commit
6e45be3d98
|
@ -21,6 +21,7 @@
|
||||||
#include <Eigen/Core>
|
#include <Eigen/Core>
|
||||||
|
|
||||||
#include <gtsam/base/DSFMap.h>
|
#include <gtsam/base/DSFMap.h>
|
||||||
|
#include <gtsam/geometry/Point2.h>
|
||||||
|
|
||||||
#include <algorithm>
|
#include <algorithm>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
@ -34,9 +35,10 @@ typedef DSFMap<IndexPair> DSFMapIndexPair;
|
||||||
typedef std::pair<size_t, size_t> ImagePair;
|
typedef std::pair<size_t, size_t> ImagePair;
|
||||||
typedef Eigen::MatrixX2i CorrespondenceIndices; // N x 2 array
|
typedef Eigen::MatrixX2i CorrespondenceIndices; // N x 2 array
|
||||||
|
|
||||||
|
//struct Keypoints;
|
||||||
using KeypointCoordinates = Eigen::MatrixX2d;
|
using KeypointCoordinates = Eigen::MatrixX2d;
|
||||||
|
|
||||||
|
|
||||||
struct Keypoints
|
struct Keypoints
|
||||||
{
|
{
|
||||||
KeypointCoordinates coordinates;
|
KeypointCoordinates coordinates;
|
||||||
|
@ -47,6 +49,10 @@ struct Keypoints
|
||||||
Keypoints(const gtsam::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none
|
Keypoints(const gtsam::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none
|
||||||
};
|
};
|
||||||
|
|
||||||
|
using KeypointsList = std::vector<Keypoints>;
|
||||||
|
using KeypointsVector = std::vector<Keypoints>; // TODO(johnwlambert): prefer KeypointsSet?
|
||||||
|
using MatchIndicesMap = std::map<ImagePair, CorrespondenceIndices>;
|
||||||
|
|
||||||
|
|
||||||
// @param camera index
|
// @param camera index
|
||||||
// @param 2d measurement
|
// @param 2d measurement
|
||||||
|
@ -54,9 +60,9 @@ struct Keypoints
|
||||||
struct NamedSfmMeasurement
|
struct NamedSfmMeasurement
|
||||||
{
|
{
|
||||||
size_t i;
|
size_t i;
|
||||||
Point2 uv;
|
gtsam::Point2 uv;
|
||||||
|
|
||||||
NamedSfmMeasurement(size_t i, Point2 uv) : i(i), uv(uv) {}
|
NamedSfmMeasurement(size_t i, gtsam::Point2 uv) : i(i), uv(uv) {}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
@ -87,10 +93,6 @@ class SfmTrack2d
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
using MatchIndicesMap = std::map<ImagePair, CorrespondenceIndices>;
|
|
||||||
using KeypointsList = std::vector<Keypoints>;
|
|
||||||
using KeypointsVector = std::vector<Keypoints>; // TODO(johnwlambert): prefer KeypointsSet?
|
|
||||||
|
|
||||||
|
|
||||||
class DsfTrackGenerator
|
class DsfTrackGenerator
|
||||||
{
|
{
|
||||||
|
|
|
@ -4,14 +4,6 @@
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
#include <gtsam/sfm/GtsfmData.h>
|
|
||||||
class GtsfmData
|
|
||||||
{
|
|
||||||
GtsfmData(const int numberImages);
|
|
||||||
void write_points(std::vector<gtsam::GtsfmImage>& images, const std::string save_dir);
|
|
||||||
void write_images(std::vector<gtsam::GtsfmImage>& images, const std::string save_dir);
|
|
||||||
};
|
|
||||||
|
|
||||||
#include <gtsam/sfm/DsfTrackGenerator.h>
|
#include <gtsam/sfm/DsfTrackGenerator.h>
|
||||||
|
|
||||||
class MatchIndicesMap {
|
class MatchIndicesMap {
|
||||||
|
@ -43,6 +35,13 @@ class Keypoints
|
||||||
}; // check if this should be a method
|
}; // check if this should be a method
|
||||||
|
|
||||||
|
|
||||||
|
class NamedSfmMeasurement
|
||||||
|
{
|
||||||
|
size_t i;
|
||||||
|
gtsam::Point2 uv;
|
||||||
|
NamedSfmMeasurement(size_t i, gtsam::Point2 uv);
|
||||||
|
};
|
||||||
|
|
||||||
class SfmTrack2d
|
class SfmTrack2d
|
||||||
{
|
{
|
||||||
void addMeasurement(const gtsam::NamedSfmMeasurement &m);
|
void addMeasurement(const gtsam::NamedSfmMeasurement &m);
|
||||||
|
|
|
@ -32,4 +32,25 @@ class TestDsfTrackGenerator(GtsamTestCase):
|
||||||
matches_dict[(1, 2)] = np.array([[2, 0], [1, 1]])
|
matches_dict[(1, 2)] = np.array([[2, 0], [1, 1]])
|
||||||
|
|
||||||
tracks = DsfTrackGenerator().generate_tracks_from_pairwise_matches(matches_dict, keypoints_list)
|
tracks = DsfTrackGenerator().generate_tracks_from_pairwise_matches(matches_dict, keypoints_list)
|
||||||
print(tracks[0])
|
|
||||||
|
assert len(tracks) == 3
|
||||||
|
|
||||||
|
# Verify track 0.
|
||||||
|
assert np.allclose(tracks[0].measurements()[0].uv, np.array([10.0, 20.0]))
|
||||||
|
assert np.allclose(tracks[0].measurements()[1].uv, np.array([50.0, 60.0]))
|
||||||
|
assert tracks[0].measurements()[0].i, 0
|
||||||
|
assert tracks[0].measurements()[1].i, 1
|
||||||
|
|
||||||
|
# Verify track 1.
|
||||||
|
assert np.allclose(tracks[1].measurements()[0].uv, np.array([30.0, 40.0]))
|
||||||
|
assert np.allclose(tracks[1].measurements()[1].uv, np.array([70.0, 80.0]))
|
||||||
|
assert np.allclose(tracks[1].measurements()[2].uv, np.array([130.0, 140.0]))
|
||||||
|
assert tracks[1].measurements()[0].i, 0
|
||||||
|
assert tracks[1].measurements()[1].i, 1
|
||||||
|
assert tracks[1].measurements()[2].i, 2
|
||||||
|
|
||||||
|
# Verify track 2.
|
||||||
|
assert np.allclose(tracks[2].measurements()[0].uv, np.array([90.0, 100.0]))
|
||||||
|
assert np.allclose(tracks[2].measurements()[1].uv, np.array([110.0, 120.0]))
|
||||||
|
assert tracks[2].measurements()[0].i, 1
|
||||||
|
assert tracks[2].measurements()[1].i, 2
|
||||||
|
|
Loading…
Reference in New Issue