add to preamble/specialization

release/4.3a0
senselessdev1 2022-09-26 11:36:39 -04:00
parent a2109a2437
commit 2434dc8ab7
6 changed files with 25 additions and 6 deletions

View File

@ -94,6 +94,10 @@ class SfmTrack2d {
} }
}; };
using SfmTrack2dVector = std::vector<gtsam::SfmTrack2d>;
/** /**
* @brief Generates point tracks from connected components in the keypoint matches graph. * @brief Generates point tracks from connected components in the keypoint matches graph.
*/ */

View File

@ -49,10 +49,20 @@ class SfmTrack2d
bool hasUniqueCameras(); bool hasUniqueCameras();
}; };
class SfmTrack2dVector {
SfmTrack2dVector();
SfmTrack2dVector(const gtsam::SfmTrack2dVector& other);
void push_back(const gtsam::SfmTrack2d& keypoints);
size_t size() const;
bool empty() const;
void clear();
gtsam::SfmTrack2d at(const size_t& index) const;
};
class DsfTrackGenerator { class DsfTrackGenerator {
DsfTrackGenerator(); DsfTrackGenerator();
std::vector<gtsam::SfmTrack2d> generate_tracks_from_pairwise_matches( const gtsam::SfmTrack2dVector generate_tracks_from_pairwise_matches(
const gtsam::MatchIndicesMap& matches_dict, const gtsam::MatchIndicesMap& matches_dict,
const gtsam::KeypointsList& keypoints_list); const gtsam::KeypointsList& keypoints_list);
}; };

View File

@ -152,7 +152,8 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON)
gtsam::CameraSetCal3Fisheye gtsam::CameraSetCal3Fisheye
gtsam::KeyPairDoubleMap gtsam::KeyPairDoubleMap
gtsam::MatchIndicesMap gtsam::MatchIndicesMap
gtsam::KeypointsList) gtsam::KeypointsList
gtsam::SfmTrack2dVector)
pybind_wrap(${GTSAM_PYTHON_UNSTABLE_TARGET} # target pybind_wrap(${GTSAM_PYTHON_UNSTABLE_TARGET} # target

View File

@ -26,6 +26,7 @@ PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::BinaryMeasurement<gtsam::Rot3>>); std::vector<gtsam::BinaryMeasurement<gtsam::Rot3>>);
PYBIND11_MAKE_OPAQUE( PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::Keypoints>); std::vector<gtsam::Keypoints>);
PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::SfmTrack2d>);
PYBIND11_MAKE_OPAQUE(gtsam::MatchIndicesMap); PYBIND11_MAKE_OPAQUE(gtsam::MatchIndicesMap);

View File

@ -37,3 +37,6 @@ py::bind_vector<
std::vector<std::pair<size_t, gtsam::Point2>>>( std::vector<std::pair<size_t, gtsam::Point2>>>(
m_, "SfmMeasurementVector" m_, "SfmMeasurementVector"
); );
py::bind_vector<
std::vector<gtsam::SfmTrack2d> >(
m_, "SfmTrack2dVector");

View File

@ -8,7 +8,7 @@ import unittest
import numpy as np import numpy as np
import gtsam import gtsam
from gtsam import DsfTrackGenerator, Keypoints, KeypointsList, MatchIndicesMap from gtsam import DsfTrackGenerator, IndexPair, Keypoints, KeypointsList, MatchIndicesMap
from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.test_case import GtsamTestCase
@ -28,8 +28,8 @@ class TestDsfTrackGenerator(GtsamTestCase):
# For each image pair (i1,i2), we provide a (K,2) matrix of corresponding image indices (k1,k2). # For each image pair (i1,i2), we provide a (K,2) matrix of corresponding image indices (k1,k2).
matches_dict = MatchIndicesMap() matches_dict = MatchIndicesMap()
matches_dict[gtsam.IndexPair(0, 1)] = np.array([[0, 0], [1, 1]]) matches_dict[IndexPair(0, 1)] = np.array([[0, 0], [1, 1]])
matches_dict[gtsam.IndexPair(1, 2)] = np.array([[2, 0], [1, 1]]) matches_dict[IndexPair(1, 2)] = np.array([[2, 0], [1, 1]])
tracks = DsfTrackGenerator().generate_tracks_from_pairwise_matches(matches_dict, keypoints_list) tracks = DsfTrackGenerator().generate_tracks_from_pairwise_matches(matches_dict, keypoints_list)
assert len(tracks) == 3 assert len(tracks) == 3