Vectorized interface

release/4.3a0
Frank Dellaert 2022-10-23 16:27:01 -07:00
parent 90c990dc33
commit 32df824920
4 changed files with 58 additions and 21 deletions

View File

@ -31,8 +31,6 @@ namespace gtsfm {
typedef Eigen::MatrixX2i CorrespondenceIndices; // N x 2 array typedef Eigen::MatrixX2i CorrespondenceIndices; // N x 2 array
using KeypointCoordinates = Eigen::MatrixX2d;
// Output of detections in an image. // Output of detections in an image.
// Coordinate system convention: // Coordinate system convention:
// 1. The x coordinate denotes the horizontal direction (+ve direction towards // 1. The x coordinate denotes the horizontal direction (+ve direction towards
@ -41,7 +39,7 @@ using KeypointCoordinates = Eigen::MatrixX2d;
// 3. Origin is at the top left corner of the image. // 3. Origin is at the top left corner of the image.
struct Keypoints { struct Keypoints {
// The (x, y) coordinates of the features, of shape Nx2. // The (x, y) coordinates of the features, of shape Nx2.
KeypointCoordinates coordinates; Eigen::MatrixX2d coordinates;
// Optional scale of the detections, of shape N. // Optional scale of the detections, of shape N.
// Note: gtsam::Vector is typedef'd for Eigen::VectorXd. // Note: gtsam::Vector is typedef'd for Eigen::VectorXd.
@ -50,7 +48,7 @@ struct Keypoints {
/// Optional confidences/responses for each detection, of shape N. /// Optional confidences/responses for each detection, of shape N.
boost::optional<gtsam::Vector> responses; boost::optional<gtsam::Vector> responses;
Keypoints(const KeypointCoordinates& coordinates) Keypoints(const Eigen::MatrixX2d& coordinates)
: coordinates(coordinates){}; // boost::none : coordinates(coordinates){}; // boost::none
}; };

View File

@ -22,6 +22,7 @@
#include <gtsam/geometry/Point2.h> #include <gtsam/geometry/Point2.h>
#include <gtsam/geometry/Point3.h> #include <gtsam/geometry/Point3.h>
#include <Eigen/Core>
#include <string> #include <string>
#include <utility> #include <utility>
#include <vector> #include <vector>
@ -90,6 +91,30 @@ struct GTSAM_EXPORT SfmTrack2d {
bool all_cameras_unique = (i == track_cam_indices.end()); bool all_cameras_unique = (i == track_cam_indices.end());
return all_cameras_unique; return all_cameras_unique;
} }
/// @}
/// @name Vectorized Interface
/// @{
/// @brief Return the measurements as a 2D matrix
Eigen::MatrixX2d measurementMatrix() const {
Eigen::MatrixX2d m(numberMeasurements(), 2);
for (size_t i = 0; i < numberMeasurements(); i++) {
m.row(i) = measurement(i).second;
}
return m;
}
/// @brief Return the camera indices of the measurements
Eigen::VectorXi indexVector() const {
Eigen::VectorXi v(numberMeasurements());
for (size_t i = 0; i < numberMeasurements(); i++) {
v(i) = measurement(i).first;
}
return v;
}
/// @}
}; };
using SfmTrack2dVector = std::vector<SfmTrack2d>; using SfmTrack2dVector = std::vector<SfmTrack2d>;

View File

@ -16,6 +16,8 @@ class SfmTrack2d {
void addMeasurement(size_t idx, const gtsam::Point2& m); void addMeasurement(size_t idx, const gtsam::Point2& m);
gtsam::SfmMeasurement measurement(size_t idx) const; gtsam::SfmMeasurement measurement(size_t idx) const;
bool hasUniqueCameras() const; bool hasUniqueCameras() const;
Eigen::MatrixX2d measurementMatrix() const;
Eigen::VectorXi indexVector() const;
}; };
virtual class SfmTrack : gtsam::SfmTrack2d { virtual class SfmTrack : gtsam::SfmTrack2d {
@ -331,8 +333,8 @@ class MatchIndicesMap {
}; };
class Keypoints { class Keypoints {
Keypoints(const gtsam::gtsfm::KeypointCoordinates& coordinates); Keypoints(const Eigen::MatrixX2d& coordinates);
gtsam::gtsfm::KeypointCoordinates coordinates; Eigen::MatrixX2d coordinates;
}; };
class KeypointsVector { class KeypointsVector {

View File

@ -7,8 +7,7 @@ import unittest
import gtsam import gtsam
import numpy as np import numpy as np
from gtsam import (IndexPair, KeypointsVector, MatchIndicesMap, Point2, from gtsam import IndexPair, KeypointsVector, MatchIndicesMap, Point2, SfmMeasurementVector, SfmTrack2d
SfmMeasurementVector, SfmTrack2d)
from gtsam.gtsfm import Keypoints from gtsam.gtsfm import Keypoints
from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.test_case import GtsamTestCase
@ -43,29 +42,42 @@ class TestDsfTrackGenerator(GtsamTestCase):
# Verify track 0. # Verify track 0.
track0 = tracks[0] track0 = tracks[0]
assert track0.numberMeasurements() == 2
np.testing.assert_allclose(track0.measurements[0][1], Point2(10, 20)) np.testing.assert_allclose(track0.measurements[0][1], Point2(10, 20))
np.testing.assert_allclose(track0.measurements[1][1], Point2(50, 60)) np.testing.assert_allclose(track0.measurements[1][1], Point2(50, 60))
assert track0.measurements[0][0] == 0 assert track0.measurements[0][0] == 0
assert track0.measurements[1][0] == 1 assert track0.measurements[1][0] == 1
assert track0.numberMeasurements() == 2 np.testing.assert_allclose(
track0.measurementMatrix(),
[
[10, 20],
[50, 60],
],
)
np.testing.assert_allclose(track0.indexVector(), [0, 1])
# Verify track 1. # Verify track 1.
track1 = tracks[1] track1 = tracks[1]
np.testing.assert_allclose(track1.measurements[0][1], Point2(30, 40)) np.testing.assert_allclose(
np.testing.assert_allclose(track1.measurements[1][1], Point2(70, 80)) track1.measurementMatrix(),
np.testing.assert_allclose(track1.measurements[2][1], Point2(130, 140)) [
assert track1.measurements[0][0] == 0 [30, 40],
assert track1.measurements[1][0] == 1 [70, 80],
assert track1.measurements[2][0] == 2 [130, 140],
assert track1.numberMeasurements() == 3 ],
)
np.testing.assert_allclose(track1.indexVector(), [0, 1, 2])
# Verify track 2. # Verify track 2.
track2 = tracks[2] track2 = tracks[2]
np.testing.assert_allclose(track2.measurements[0][1], Point2(90, 100)) np.testing.assert_allclose(
np.testing.assert_allclose(track2.measurements[1][1], Point2(110, 120)) track2.measurementMatrix(),
assert track2.measurements[0][0] == 1 [
assert track2.measurements[1][0] == 2 [90, 100],
assert track2.numberMeasurements() == 2 [110, 120],
],
)
np.testing.assert_allclose(track2.indexVector(), [1, 2])
class TestSfmTrack2d(GtsamTestCase): class TestSfmTrack2d(GtsamTestCase):