Merge pull request #1316 from borglab/fix/track-wrapper

release/4.3a0
Varun Agrawal 2022-10-26 19:54:53 -04:00 committed by GitHub
commit 8b2639a69b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 6 additions and 4 deletions

View File

@ -329,7 +329,7 @@ class MatchIndicesMap {
size_t size() const; size_t size() const;
bool empty() const; bool empty() const;
void clear(); void clear();
gtsam::gtsfm::CorrespondenceIndices at(const pair<size_t, size_t>& keypair) const; gtsam::gtsfm::CorrespondenceIndices at(const gtsam::IndexPair& keypair) const;
}; };
class Keypoints { class Keypoints {
@ -350,6 +350,7 @@ class KeypointsVector {
gtsam::SfmTrack2dVector tracksFromPairwiseMatches( gtsam::SfmTrack2dVector tracksFromPairwiseMatches(
const gtsam::gtsfm::MatchIndicesMap& matches_dict, 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 gtsfm
} // namespace gtsam } // namespace gtsam

View File

@ -7,7 +7,8 @@ import unittest
import gtsam import gtsam
import numpy as np import numpy as np
from gtsam import IndexPair, KeypointsVector, MatchIndicesMap, Point2, SfmMeasurementVector, SfmTrack2d from gtsam import (IndexPair, KeypointsVector, MatchIndicesMap, Point2,
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
@ -84,12 +85,12 @@ class TestSfmTrack2d(GtsamTestCase):
"""Tests for SfmTrack2d.""" """Tests for SfmTrack2d."""
def test_sfm_track_2d_constructor(self) -> None: def test_sfm_track_2d_constructor(self) -> None:
""" """ """Test construction of 2D SfM track."""
measurements = SfmMeasurementVector() measurements = SfmMeasurementVector()
measurements.append((0, Point2(10, 20))) measurements.append((0, Point2(10, 20)))
track = SfmTrack2d(measurements=measurements) track = SfmTrack2d(measurements=measurements)
track.measurement(0) track.measurement(0)
track.numberMeasurements() == 1 assert track.numberMeasurements() == 1
if __name__ == "__main__": if __name__ == "__main__":