From cafab61fecb8fcdf14065c8de1fd8a340504b10c Mon Sep 17 00:00:00 2001 From: senselessdev1 Date: Tue, 27 Sep 2022 10:29:36 -0400 Subject: [PATCH] expand tests --- gtsam/sfm/sfm.i | 4 +++ python/gtsam/preamble/sfm.h | 5 ---- python/gtsam/tests/test_DsfTrackGenerator.py | 26 +++++++++++++++++++- 3 files changed, 29 insertions(+), 6 deletions(-) diff --git a/gtsam/sfm/sfm.i b/gtsam/sfm/sfm.i index 155a551bd..6fd380b3c 100644 --- a/gtsam/sfm/sfm.i +++ b/gtsam/sfm/sfm.i @@ -54,8 +54,12 @@ class NamedSfmMeasurementVector { class SfmTrack2d { + SfmTrack2d(); + SfmTrack2d(std::vector &measurements); + size_t numberMeasurements() const; void addMeasurement(const gtsam::NamedSfmMeasurement &m); std::vector measurements(); + gtsam::NamedSfmMeasurement measurement(size_t idx) const; bool hasUniqueCameras(); }; diff --git a/python/gtsam/preamble/sfm.h b/python/gtsam/preamble/sfm.h index 429b794b8..91c9fc418 100644 --- a/python/gtsam/preamble/sfm.h +++ b/python/gtsam/preamble/sfm.h @@ -17,7 +17,6 @@ PYBIND11_MAKE_OPAQUE( std::vector); - PYBIND11_MAKE_OPAQUE( std::vector); PYBIND11_MAKE_OPAQUE( @@ -26,10 +25,6 @@ PYBIND11_MAKE_OPAQUE( std::vector>); PYBIND11_MAKE_OPAQUE( std::vector); -// PYBIND11_MAKE_OPAQUE( -// std::vector); - PYBIND11_MAKE_OPAQUE(gtsam::MatchIndicesMap); - PYBIND11_MAKE_OPAQUE( std::vector); \ No newline at end of file diff --git a/python/gtsam/tests/test_DsfTrackGenerator.py b/python/gtsam/tests/test_DsfTrackGenerator.py index 41394f17a..3d4188284 100644 --- a/python/gtsam/tests/test_DsfTrackGenerator.py +++ b/python/gtsam/tests/test_DsfTrackGenerator.py @@ -8,7 +8,16 @@ import unittest import numpy as np import gtsam -from gtsam import DsfTrackGenerator, IndexPair, Keypoints, KeypointsList, MatchIndicesMap +from gtsam import ( + DsfTrackGenerator, + IndexPair, + Keypoints, + KeypointsList, + MatchIndicesMap, + NamedSfmMeasurement, + NamedSfmMeasurementVector, + SfmTrack2d, +) from gtsam.utils.test_case import GtsamTestCase @@ -39,6 +48,7 @@ class TestDsfTrackGenerator(GtsamTestCase): 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 + assert tracks[0].numberMeasurements() == 2 # Verify track 1. assert np.allclose(tracks[1].measurements()[0].uv, np.array([30.0, 40.0])) @@ -47,9 +57,23 @@ class TestDsfTrackGenerator(GtsamTestCase): assert tracks[1].measurements()[0].i == 0 assert tracks[1].measurements()[1].i == 1 assert tracks[1].measurements()[2].i == 2 + assert tracks[1].numberMeasurements() == 3 # 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 + assert tracks[2].numberMeasurements() == 2 + + +class TestSfmTrack2d(GtsamTestCase): + """Tests for SfmTrack2d.""" + + def test_sfm_track_2d_constructor(self) -> None: + """ """ + measurements = NamedSfmMeasurementVector() + measurements.append(NamedSfmMeasurement(i=0, uv=np.array([10.0, 20.0]))) + track = SfmTrack2d(measurements=measurements) + track.measurement(0) + track.numberMeasurements() == 1