use gtsam.gtsfm namespace for new API

release/4.3a0
senselessdev1 2022-10-13 01:07:41 -04:00
parent 7dee1af5b4
commit f9971f5049
6 changed files with 51 additions and 52 deletions

View File

@ -30,6 +30,8 @@
namespace gtsam {
namespace gtsfm {
typedef DSFMap<IndexPair> DSFMapIndexPair;
typedef Eigen::MatrixX2i CorrespondenceIndices; // N x 2 array
@ -54,7 +56,7 @@ struct Keypoints {
/// Optional confidences/responses for each detection, of shape N.
boost::optional<gtsam::Vector> responses;
Keypoints(const gtsam::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none
Keypoints(const gtsam::gtsfm::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none
};
using KeypointsVector = std::vector<Keypoints>;
@ -119,7 +121,7 @@ class SfmTrack2d {
}
};
using SfmTrack2dVector = std::vector<gtsam::SfmTrack2d>;
using SfmTrack2dVector = std::vector<gtsam::gtsfm::SfmTrack2d>;
using NamedSfmMeasurementVector = std::vector<NamedSfmMeasurement>;
@ -216,5 +218,7 @@ class DsfTrackGenerator {
}
};
}///\namespace gtsfm
} // namespace gtsam

View File

@ -4,34 +4,36 @@
namespace gtsam {
namespace gtsfm {
#include <gtsam/sfm/DsfTrackGenerator.h>
class MatchIndicesMap {
MatchIndicesMap();
MatchIndicesMap(const gtsam::MatchIndicesMap& other);
MatchIndicesMap(const gtsam::gtsfm::MatchIndicesMap& other);
size_t size() const;
bool empty() const;
void clear();
gtsam::CorrespondenceIndices at(const pair<size_t, size_t>& keypair) const;
gtsam::gtsfm::CorrespondenceIndices at(const pair<size_t, size_t>& keypair) const;
};
class Keypoints
{
Keypoints(const gtsam::KeypointCoordinates& coordinates);
gtsam::KeypointCoordinates coordinates;
Keypoints(const gtsam::gtsfm::KeypointCoordinates& coordinates);
gtsam::gtsfm::KeypointCoordinates coordinates;
}; // check if this should be a method
class KeypointsVector {
KeypointsVector();
KeypointsVector(const gtsam::KeypointsVector& other);
void push_back(const gtsam::Keypoints& keypoints);
KeypointsVector(const gtsam::gtsfm::KeypointsVector& other);
void push_back(const gtsam::gtsfm::Keypoints& keypoints);
size_t size() const;
bool empty() const;
void clear();
gtsam::Keypoints at(const size_t& index) const;
gtsam::gtsfm::Keypoints at(const size_t& index) const;
};
@ -44,44 +46,44 @@ class NamedSfmMeasurement
class NamedSfmMeasurementVector {
NamedSfmMeasurementVector();
NamedSfmMeasurementVector(const gtsam::NamedSfmMeasurementVector& other);
void push_back(const gtsam::NamedSfmMeasurement& measurement);
NamedSfmMeasurementVector(const gtsam::gtsfm::NamedSfmMeasurementVector& other);
void push_back(const gtsam::gtsfm::NamedSfmMeasurement& measurement);
size_t size() const;
bool empty() const;
void clear();
gtsam::NamedSfmMeasurement at(const size_t& index) const;
gtsam::gtsfm::NamedSfmMeasurement at(const size_t& index) const;
};
class SfmTrack2d
{
SfmTrack2d();
SfmTrack2d(std::vector<gtsam::NamedSfmMeasurement> &measurements);
SfmTrack2d(std::vector<gtsam::gtsfm::NamedSfmMeasurement> &measurements);
size_t numberMeasurements() const;
void addMeasurement(const gtsam::NamedSfmMeasurement &m);
std::vector<gtsam::NamedSfmMeasurement> measurements();
gtsam::NamedSfmMeasurement measurement(size_t idx) const;
void addMeasurement(const gtsam::gtsfm::NamedSfmMeasurement &m);
std::vector<gtsam::gtsfm::NamedSfmMeasurement> measurements();
gtsam::gtsfm::NamedSfmMeasurement measurement(size_t idx) const;
bool hasUniqueCameras();
};
class SfmTrack2dVector {
SfmTrack2dVector();
SfmTrack2dVector(const gtsam::SfmTrack2dVector& other);
void push_back(const gtsam::SfmTrack2d& track);
SfmTrack2dVector(const gtsam::gtsfm::SfmTrack2dVector& other);
void push_back(const gtsam::gtsfm::SfmTrack2d& track);
size_t size() const;
bool empty() const;
void clear();
gtsam::SfmTrack2d at(const size_t& index) const;
gtsam::gtsfm::SfmTrack2d at(const size_t& index) const;
};
class DsfTrackGenerator {
DsfTrackGenerator();
const gtsam::SfmTrack2dVector generate_tracks_from_pairwise_matches(
const gtsam::MatchIndicesMap& matches_dict,
const gtsam::KeypointsVector& keypoints_list,
const gtsam::gtsfm::SfmTrack2dVector generate_tracks_from_pairwise_matches(
const gtsam::gtsfm::MatchIndicesMap& matches_dict,
const gtsam::gtsfm::KeypointsVector& keypoints_list,
bool verbose = false);
};
}///\namespace gtsfm
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h>

View File

@ -52,10 +52,10 @@ set(ignore
gtsam::BinaryMeasurementsRot3
gtsam::DiscreteKey
gtsam::KeyPairDoubleMap
gtsam::MatchIndicesMap
gtsam::KeypointsVector
gtsam::SfmTrack2dVector
gtsam::NamedSfmMeasurementVector)
gtsam::gtsfm::MatchIndicesMap
gtsam::gtsfm::KeypointsVector
gtsam::gtsfm::SfmTrack2dVector
gtsam::gtsfm::NamedSfmMeasurementVector)
set(interface_headers
${PROJECT_SOURCE_DIR}/gtsam/gtsam.i
@ -153,10 +153,10 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON)
gtsam::CameraSetCal3Unified
gtsam::CameraSetCal3Fisheye
gtsam::KeyPairDoubleMap
gtsam::MatchIndicesMap
gtsam::KeypointsVector
gtsam::SfmTrack2dVector
gtsam::NamedSfmMeasurementVector)
gtsam::gtsfm::MatchIndicesMap
gtsam::gtsfm::KeypointsVector
gtsam::gtsfm::SfmTrack2dVector
gtsam::gtsfm::NamedSfmMeasurementVector)
pybind_wrap(${GTSAM_PYTHON_UNSTABLE_TARGET} # target

View File

@ -24,7 +24,7 @@ PYBIND11_MAKE_OPAQUE(
PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::BinaryMeasurement<gtsam::Rot3>>);
PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::Keypoints>);
PYBIND11_MAKE_OPAQUE(gtsam::MatchIndicesMap);
std::vector<gtsam::gtsfm::Keypoints>);
PYBIND11_MAKE_OPAQUE(gtsam::gtsfm::MatchIndicesMap);
PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::NamedSfmMeasurement>);
std::vector<gtsam::gtsfm::NamedSfmMeasurement>);

View File

@ -18,29 +18,25 @@ py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(
py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Rot3> > >(
m_, "BinaryMeasurementsRot3");
py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap");
py::bind_map<gtsam::MatchIndicesMap>(m_, "MatchIndicesMap");
py::bind_vector<
std::vector<gtsam::Keypoints> >(
m_, "KeypointsVector");
py::bind_vector<
std::vector<gtsam::SfmTrack> >(
m_, "SfmTracks");
py::bind_vector<
std::vector<gtsam::SfmCamera> >(
m_, "SfmCameras");
py::bind_vector<
std::vector<std::pair<size_t, gtsam::Point2>>>(
m_, "SfmMeasurementVector"
);
py::bind_vector<
std::vector<gtsam::SfmTrack2d> >(
m_, "SfmTrack2dVector");
py::bind_vector<
std::vector<gtsam::NamedSfmMeasurement> >(
std::vector<gtsam::gtsfm::SfmTrack2d> >(
m_, "SfmTrack2dVector");
py::bind_vector<
std::vector<gtsam::gtsfm::NamedSfmMeasurement> >(
m_, "NamedSfmMeasurementVector");
py::bind_map<gtsam::gtsfm::MatchIndicesMap>(m_, "MatchIndicesMap");
py::bind_vector<
std::vector<gtsam::gtsfm::Keypoints> >(
m_, "KeypointsVector");

View File

@ -8,14 +8,11 @@ import unittest
import numpy as np
import gtsam
from gtsam import (
from gtsam import IndexPair, KeypointsVector, MatchIndicesMap, NamedSfmMeasurementVector
from gtsam.gtsam.gtsfm import (
DsfTrackGenerator,
IndexPair,
Keypoints,
KeypointsVector,
MatchIndicesMap,
NamedSfmMeasurement,
NamedSfmMeasurementVector,
SfmTrack2d,
)
from gtsam.utils.test_case import GtsamTestCase