expand tests

release/4.3a0
senselessdev1 2022-09-27 10:29:36 -04:00
parent 6eb4ada2fd
commit cafab61fec
3 changed files with 29 additions and 6 deletions

View File

@ -54,8 +54,12 @@ class NamedSfmMeasurementVector {
class SfmTrack2d
{
SfmTrack2d();
SfmTrack2d(std::vector<gtsam::NamedSfmMeasurement> &measurements);
size_t numberMeasurements() const;
void addMeasurement(const gtsam::NamedSfmMeasurement &m);
std::vector<gtsam::NamedSfmMeasurement> measurements();
gtsam::NamedSfmMeasurement measurement(size_t idx) const;
bool hasUniqueCameras();
};

View File

@ -17,7 +17,6 @@
PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::SfmTrack>);
PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::SfmCamera>);
PYBIND11_MAKE_OPAQUE(
@ -26,10 +25,6 @@ PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::BinaryMeasurement<gtsam::Rot3>>);
PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::Keypoints>);
// PYBIND11_MAKE_OPAQUE(
// std::vector<gtsam::SfmTrack2d>);
PYBIND11_MAKE_OPAQUE(gtsam::MatchIndicesMap);
PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::NamedSfmMeasurement>);

View File

@ -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