Addressed review comments - removed class in favor of free function

release/4.3a0
Frank Dellaert 2022-10-23 11:37:37 -07:00
parent ca451141c0
commit f68f0dbe41
5 changed files with 26 additions and 44 deletions

View File

@ -98,7 +98,7 @@ static std::vector<SfmTrack2d> tracksFromDSF(const DSFMapIndexPair& dsf,
* correspondence indices, from each image.
* @param Length-N list of keypoints, for N images/cameras.
*/
std::vector<SfmTrack2d> DsfTrackGenerator::tracksFromPairwiseMatches(
std::vector<SfmTrack2d> tracksFromPairwiseMatches(
const MatchIndicesMap& matches, const KeypointsVector& keypoints,
bool verbose) {
// Generate the DSF to form tracks.
@ -121,7 +121,7 @@ std::vector<SfmTrack2d> DsfTrackGenerator::tracksFromPairwiseMatches(
double erroneous_percentage = static_cast<float>(erroneous_track_count) /
static_cast<float>(tracks2d.size()) * 100;
// TODO(johnwlambert): restrict decimal places to 2 decimals.
std::cout << std::fixed << std::setprecision(2);
std::cout << "DSF Union-Find: " << erroneous_percentage;
std::cout << "% of tracks discarded from multiple obs. in a single image."
<< std::endl;

View File

@ -31,7 +31,6 @@ namespace gtsfm {
typedef Eigen::MatrixX2i CorrespondenceIndices; // N x 2 array
// struct Keypoints;
using KeypointCoordinates = Eigen::MatrixX2d;
// Output of detections in an image.
@ -61,15 +60,6 @@ using KeypointsVector = std::vector<Keypoints>;
using MatchIndicesMap = std::map<IndexPair, CorrespondenceIndices>;
/**
* @brief Generates point tracks from connected components in the keypoint
* matches graph.
*/
class DsfTrackGenerator {
public:
/** Default constructor. */
DsfTrackGenerator() = default;
/**
* @brief Creates a list of tracks from 2d point correspondences.
*
* Creates a disjoint-set forest (DSF) and 2d tracks from pairwise matches.
@ -81,10 +71,9 @@ class DsfTrackGenerator {
* correspondence indices, from each image.
* @param Length-N list of keypoints, for N images/cameras.
*/
static std::vector<SfmTrack2d> tracksFromPairwiseMatches(
std::vector<SfmTrack2d> tracksFromPairwiseMatches(
const MatchIndicesMap& matches, const KeypointsVector& keypoints,
bool verbose = false);
};
} // namespace gtsfm

View File

@ -77,7 +77,7 @@ struct GTSAM_EXPORT SfmTrack2d {
const SiftIndex& siftIndex(size_t idx) const { return siftIndices[idx]; }
/**
* @brief Validates the track by checking that no two measurements are from
* @brief Check that no two measurements are from the same camera.
* @returns boolean result of the validation.
*/
bool hasUniqueCameras() const {

View File

@ -5,18 +5,17 @@
namespace gtsam {
#include <gtsam/sfm/SfmTrack.h>
class SfmTrack2d
{
class SfmTrack2d {
std::vector<pair<size_t, gtsam::Point2>> measurements;
SfmTrack2d();
SfmTrack2d(std::vector<gtsam::SfmMeasurement> &measurements);
SfmTrack2d(const std::vector<gtsam::SfmMeasurement>& measurements);
size_t numberMeasurements() const;
pair<size_t, gtsam::Point2> measurement(size_t idx) const;
pair<size_t, size_t> siftIndex(size_t idx) const;
void addMeasurement(size_t idx, const gtsam::Point2& m);
gtsam::SfmMeasurement measurement(size_t idx) const;
bool hasUniqueCameras();
bool hasUniqueCameras() const;
};
virtual class SfmTrack : gtsam::SfmTrack2d {
@ -331,13 +330,10 @@ class MatchIndicesMap {
gtsam::gtsfm::CorrespondenceIndices at(const pair<size_t, size_t>& keypair) const;
};
class Keypoints
{
class Keypoints {
Keypoints(const gtsam::gtsfm::KeypointCoordinates& coordinates);
gtsam::gtsfm::KeypointCoordinates coordinates;
}; // check if this should be a method
};
class KeypointsVector {
KeypointsVector();
@ -349,13 +345,9 @@ class KeypointsVector {
gtsam::gtsfm::Keypoints at(const size_t& index) const;
};
class DsfTrackGenerator {
DsfTrackGenerator();
const gtsam::SfmTrack2dVector tracksFromPairwiseMatches(
gtsam::SfmTrack2dVector tracksFromPairwiseMatches(
const gtsam::gtsfm::MatchIndicesMap& matches_dict,
const gtsam::gtsfm::KeypointsVector& keypoints_list,
bool verbose = false);
};
const gtsam::gtsfm::KeypointsVector& keypoints_list, bool verbose = false);
} // namespace gtsfm
} // namespace gtsam

View File

@ -5,10 +5,11 @@ Authors: John Lambert
import unittest
import gtsam
import numpy as np
from gtsam import (IndexPair, KeypointsVector, MatchIndicesMap, Point2,
SfmMeasurementVector, SfmTrack2d)
from gtsam.gtsfm import DsfTrackGenerator, Keypoints
from gtsam.gtsfm import Keypoints
from gtsam.utils.test_case import GtsamTestCase
@ -33,7 +34,7 @@ class TestDsfTrackGenerator(GtsamTestCase):
matches_dict[IndexPair(0, 1)] = np.array([[0, 0], [1, 1]])
matches_dict[IndexPair(1, 2)] = np.array([[2, 0], [1, 1]])
tracks = DsfTrackGenerator().tracksFromPairwiseMatches(
tracks = gtsam.gtsfm.tracksFromPairwiseMatches(
matches_dict,
keypoints_list,
verbose=False,