Merge pull request #1185 from borglab/feature/sfm_utils
Added some utilities for better using the SfM parts of GTSAM in Pythonrelease/4.3a0
commit
63ffeafd0d
|
|
@ -547,6 +547,12 @@ class EssentialMatrix {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
EssentialMatrix(const gtsam::Rot3& aRb, const gtsam::Unit3& aTb);
|
EssentialMatrix(const gtsam::Rot3& aRb, const gtsam::Unit3& aTb);
|
||||||
|
|
||||||
|
// Constructors from Pose3
|
||||||
|
gtsam::EssentialMatrix FromPose3(const gtsam::Pose3& _1P2_);
|
||||||
|
|
||||||
|
gtsam::EssentialMatrix FromPose3(const gtsam::Pose3& _1P2_,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> H);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s = "") const;
|
void print(string s = "") const;
|
||||||
bool equals(const gtsam::EssentialMatrix& pose, double tol) const;
|
bool equals(const gtsam::EssentialMatrix& pose, double tol) const;
|
||||||
|
|
@ -904,6 +910,12 @@ class PinholeCamera {
|
||||||
Eigen::Ref<Eigen::MatrixXd> Dresult_dp,
|
Eigen::Ref<Eigen::MatrixXd> Dresult_dp,
|
||||||
Eigen::Ref<Eigen::MatrixXd> Dresult_ddepth,
|
Eigen::Ref<Eigen::MatrixXd> Dresult_ddepth,
|
||||||
Eigen::Ref<Eigen::MatrixXd> Dresult_dcal);
|
Eigen::Ref<Eigen::MatrixXd> Dresult_dcal);
|
||||||
|
|
||||||
|
gtsam::Point2 reprojectionError(const gtsam::Point3& pw, const gtsam::Point2& measured,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dpose,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dpoint,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dcal);
|
||||||
|
|
||||||
double range(const gtsam::Point3& point);
|
double range(const gtsam::Point3& point);
|
||||||
double range(const gtsam::Point3& point, Eigen::Ref<Eigen::MatrixXd> Dcamera,
|
double range(const gtsam::Point3& point, Eigen::Ref<Eigen::MatrixXd> Dcamera,
|
||||||
Eigen::Ref<Eigen::MatrixXd> Dpoint);
|
Eigen::Ref<Eigen::MatrixXd> Dpoint);
|
||||||
|
|
@ -914,7 +926,74 @@ class PinholeCamera {
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Forward declaration of PinholeCameraCalX is defined here.
|
||||||
|
#include <gtsam/geometry/SimpleCamera.h>
|
||||||
|
// Some typedefs for common camera types
|
||||||
|
// PinholeCameraCal3_S2 is the same as SimpleCamera above
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
|
||||||
|
typedef gtsam::PinholeCamera<gtsam::Cal3Fisheye> PinholeCameraCal3Fisheye;
|
||||||
|
|
||||||
|
#include <gtsam/geometry/PinholePose.h>
|
||||||
|
template <CALIBRATION>
|
||||||
|
class PinholePose {
|
||||||
|
// Standard Constructors and Named Constructors
|
||||||
|
PinholePose();
|
||||||
|
PinholePose(const gtsam::PinholePose<CALIBRATION> other);
|
||||||
|
PinholePose(const gtsam::Pose3& pose);
|
||||||
|
PinholePose(const gtsam::Pose3& pose, const CALIBRATION* K);
|
||||||
|
static This Level(const gtsam::Pose2& pose, double height);
|
||||||
|
static This Lookat(const gtsam::Point3& eye, const gtsam::Point3& target,
|
||||||
|
const gtsam::Point3& upVector, const CALIBRATION* K);
|
||||||
|
|
||||||
|
// Testable
|
||||||
|
void print(string s = "PinholePose") const;
|
||||||
|
bool equals(const This& camera, double tol) const;
|
||||||
|
|
||||||
|
// Standard Interface
|
||||||
|
gtsam::Pose3 pose() const;
|
||||||
|
CALIBRATION calibration() const;
|
||||||
|
|
||||||
|
// Manifold
|
||||||
|
This retract(Vector d) const;
|
||||||
|
Vector localCoordinates(const This& T2) const;
|
||||||
|
size_t dim() const;
|
||||||
|
static size_t Dim();
|
||||||
|
|
||||||
|
// Transformations and measurement functions
|
||||||
|
static gtsam::Point2 Project(const gtsam::Point3& cameraPoint);
|
||||||
|
pair<gtsam::Point2, bool> projectSafe(const gtsam::Point3& pw) const;
|
||||||
|
gtsam::Point2 project(const gtsam::Point3& point);
|
||||||
|
gtsam::Point2 project(const gtsam::Point3& point,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dpose,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dpoint,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dcal);
|
||||||
|
gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const;
|
||||||
|
gtsam::Point3 backproject(const gtsam::Point2& p, double depth,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dresult_dpose,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dresult_dp,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dresult_ddepth,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dresult_dcal);
|
||||||
|
double range(const gtsam::Point3& point);
|
||||||
|
double range(const gtsam::Point3& point, Eigen::Ref<Eigen::MatrixXd> Dcamera,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dpoint);
|
||||||
|
double range(const gtsam::Pose3& pose);
|
||||||
|
double range(const gtsam::Pose3& pose, Eigen::Ref<Eigen::MatrixXd> Dcamera,
|
||||||
|
Eigen::Ref<Eigen::MatrixXd> Dpose);
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3_S2> PinholePoseCal3_S2;
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3DS2> PinholePoseCal3DS2;
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3Unified> PinholePoseCal3Unified;
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3Bundler> PinholePoseCal3Bundler;
|
||||||
|
typedef gtsam::PinholePose<gtsam::Cal3Fisheye> PinholePoseCal3Fisheye;
|
||||||
|
|
||||||
#include <gtsam/geometry/Similarity2.h>
|
#include <gtsam/geometry/Similarity2.h>
|
||||||
class Similarity2 {
|
class Similarity2 {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
|
|
@ -961,16 +1040,6 @@ class Similarity3 {
|
||||||
double scale() const;
|
double scale() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
// Forward declaration of PinholeCameraCalX is defined here.
|
|
||||||
#include <gtsam/geometry/SimpleCamera.h>
|
|
||||||
// Some typedefs for common camera types
|
|
||||||
// PinholeCameraCal3_S2 is the same as SimpleCamera above
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
|
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3Fisheye> PinholeCameraCal3Fisheye;
|
|
||||||
|
|
||||||
template <T>
|
template <T>
|
||||||
class CameraSet {
|
class CameraSet {
|
||||||
CameraSet();
|
CameraSet();
|
||||||
|
|
|
||||||
|
|
@ -671,6 +671,10 @@ virtual class DummyPreconditionerParameters : gtsam::PreconditionerParameters {
|
||||||
DummyPreconditionerParameters();
|
DummyPreconditionerParameters();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
virtual class BlockJacobiPreconditionerParameters : gtsam::PreconditionerParameters {
|
||||||
|
BlockJacobiPreconditionerParameters();
|
||||||
|
};
|
||||||
|
|
||||||
#include <gtsam/linear/PCGSolver.h>
|
#include <gtsam/linear/PCGSolver.h>
|
||||||
virtual class PCGSolverParameters : gtsam::ConjugateGradientParameters {
|
virtual class PCGSolverParameters : gtsam::ConjugateGradientParameters {
|
||||||
PCGSolverParameters();
|
PCGSolverParameters();
|
||||||
|
|
|
||||||
|
|
@ -226,6 +226,10 @@ class Values {
|
||||||
void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
|
void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
|
||||||
void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
|
void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
|
||||||
void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
|
void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
|
||||||
|
void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3_S2>& camera);
|
||||||
|
void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
|
||||||
|
void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3Fisheye>& camera);
|
||||||
|
void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
|
||||||
void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
|
void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
|
||||||
void insert(size_t j, const gtsam::NavState& nav_state);
|
void insert(size_t j, const gtsam::NavState& nav_state);
|
||||||
void insert(size_t j, double c);
|
void insert(size_t j, double c);
|
||||||
|
|
@ -269,6 +273,10 @@ class Values {
|
||||||
void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
|
void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
|
||||||
void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
|
void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
|
||||||
void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
|
void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
|
||||||
|
void update(size_t j, const gtsam::PinholePose<gtsam::Cal3_S2>& camera);
|
||||||
|
void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
|
||||||
|
void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Fisheye>& camera);
|
||||||
|
void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
|
||||||
void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
|
void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
|
||||||
void update(size_t j, const gtsam::NavState& nav_state);
|
void update(size_t j, const gtsam::NavState& nav_state);
|
||||||
void update(size_t j, Vector vector);
|
void update(size_t j, Vector vector);
|
||||||
|
|
@ -310,6 +318,10 @@ class Values {
|
||||||
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
|
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
|
||||||
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
|
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
|
||||||
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
|
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
|
||||||
|
void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3_S2>& camera);
|
||||||
|
void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
|
||||||
|
void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3Fisheye>& camera);
|
||||||
|
void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
|
||||||
void insert_or_assign(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
|
void insert_or_assign(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
|
||||||
void insert_or_assign(size_t j, const gtsam::NavState& nav_state);
|
void insert_or_assign(size_t j, const gtsam::NavState& nav_state);
|
||||||
void insert_or_assign(size_t j, Vector vector);
|
void insert_or_assign(size_t j, Vector vector);
|
||||||
|
|
@ -351,6 +363,10 @@ class Values {
|
||||||
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
||||||
gtsam::PinholeCamera<gtsam::Cal3Fisheye>,
|
gtsam::PinholeCamera<gtsam::Cal3Fisheye>,
|
||||||
gtsam::PinholeCamera<gtsam::Cal3Unified>,
|
gtsam::PinholeCamera<gtsam::Cal3Unified>,
|
||||||
|
gtsam::PinholePose<gtsam::Cal3_S2>,
|
||||||
|
gtsam::PinholePose<gtsam::Cal3Bundler>,
|
||||||
|
gtsam::PinholePose<gtsam::Cal3Fisheye>,
|
||||||
|
gtsam::PinholePose<gtsam::Cal3Unified>,
|
||||||
gtsam::imuBias::ConstantBias,
|
gtsam::imuBias::ConstantBias,
|
||||||
gtsam::NavState,
|
gtsam::NavState,
|
||||||
Vector,
|
Vector,
|
||||||
|
|
|
||||||
|
|
@ -77,10 +77,14 @@ struct GTSAM_EXPORT SfmData {
|
||||||
size_t numberCameras() const { return cameras.size(); }
|
size_t numberCameras() const { return cameras.size(); }
|
||||||
|
|
||||||
/// The track formed by series of landmark measurements
|
/// The track formed by series of landmark measurements
|
||||||
SfmTrack track(size_t idx) const { return tracks[idx]; }
|
const SfmTrack& track(size_t idx) const { return tracks[idx]; }
|
||||||
|
|
||||||
/// The camera pose at frame index `idx`
|
/// The camera pose at frame index `idx`
|
||||||
SfmCamera camera(size_t idx) const { return cameras[idx]; }
|
const SfmCamera& camera(size_t idx) const { return cameras[idx]; }
|
||||||
|
|
||||||
|
/// Getters
|
||||||
|
const std::vector<SfmCamera>& cameraList() const { return cameras; }
|
||||||
|
const std::vector<SfmTrack>& trackList() const { return tracks; }
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Create projection factors using keys i and P(j)
|
* @brief Create projection factors using keys i and P(j)
|
||||||
|
|
|
||||||
|
|
@ -9,6 +9,8 @@ class SfmTrack {
|
||||||
SfmTrack();
|
SfmTrack();
|
||||||
SfmTrack(const gtsam::Point3& pt);
|
SfmTrack(const gtsam::Point3& pt);
|
||||||
const Point3& point3() const;
|
const Point3& point3() const;
|
||||||
|
|
||||||
|
Point3 p;
|
||||||
|
|
||||||
double r;
|
double r;
|
||||||
double g;
|
double g;
|
||||||
|
|
@ -34,12 +36,15 @@ class SfmData {
|
||||||
static gtsam::SfmData FromBundlerFile(string filename);
|
static gtsam::SfmData FromBundlerFile(string filename);
|
||||||
static gtsam::SfmData FromBalFile(string filename);
|
static gtsam::SfmData FromBalFile(string filename);
|
||||||
|
|
||||||
|
std::vector<gtsam::SfmTrack>& trackList() const;
|
||||||
|
std::vector<gtsam::PinholeCamera<gtsam::Cal3Bundler>>& cameraList() const;
|
||||||
|
|
||||||
void addTrack(const gtsam::SfmTrack& t);
|
void addTrack(const gtsam::SfmTrack& t);
|
||||||
void addCamera(const gtsam::SfmCamera& cam);
|
void addCamera(const gtsam::SfmCamera& cam);
|
||||||
size_t numberTracks() const;
|
size_t numberTracks() const;
|
||||||
size_t numberCameras() const;
|
size_t numberCameras() const;
|
||||||
gtsam::SfmTrack track(size_t idx) const;
|
gtsam::SfmTrack& track(size_t idx) const;
|
||||||
gtsam::PinholeCamera<gtsam::Cal3Bundler> camera(size_t idx) const;
|
gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera(size_t idx) const;
|
||||||
|
|
||||||
gtsam::NonlinearFactorGraph generalSfmFactors(
|
gtsam::NonlinearFactorGraph generalSfmFactors(
|
||||||
const gtsam::SharedNoiseModel& model =
|
const gtsam::SharedNoiseModel& model =
|
||||||
|
|
@ -91,6 +96,13 @@ class BinaryMeasurementsUnit3 {
|
||||||
void push_back(const gtsam::BinaryMeasurement<gtsam::Unit3>& measurement);
|
void push_back(const gtsam::BinaryMeasurement<gtsam::Unit3>& measurement);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
class BinaryMeasurementsRot3 {
|
||||||
|
BinaryMeasurementsRot3();
|
||||||
|
size_t size() const;
|
||||||
|
gtsam::BinaryMeasurement<gtsam::Rot3> at(size_t idx) const;
|
||||||
|
void push_back(const gtsam::BinaryMeasurement<gtsam::Rot3>& measurement);
|
||||||
|
};
|
||||||
|
|
||||||
#include <gtsam/sfm/ShonanAveraging.h>
|
#include <gtsam/sfm/ShonanAveraging.h>
|
||||||
|
|
||||||
// TODO(frank): copy/pasta below until we have integer template paremeters in
|
// TODO(frank): copy/pasta below until we have integer template paremeters in
|
||||||
|
|
@ -184,6 +196,10 @@ class ShonanAveraging2 {
|
||||||
};
|
};
|
||||||
|
|
||||||
class ShonanAveraging3 {
|
class ShonanAveraging3 {
|
||||||
|
ShonanAveraging3(
|
||||||
|
const std::vector<gtsam::BinaryMeasurement<gtsam::Rot3>>& measurements,
|
||||||
|
const gtsam::ShonanAveragingParameters3& parameters =
|
||||||
|
gtsam::ShonanAveragingParameters3());
|
||||||
ShonanAveraging3(string g2oFile);
|
ShonanAveraging3(string g2oFile);
|
||||||
ShonanAveraging3(string g2oFile,
|
ShonanAveraging3(string g2oFile,
|
||||||
const gtsam::ShonanAveragingParameters3& parameters);
|
const gtsam::ShonanAveragingParameters3& parameters);
|
||||||
|
|
|
||||||
|
|
@ -223,6 +223,7 @@ parse3DFactors(const std::string &filename,
|
||||||
size_t maxIndex = 0);
|
size_t maxIndex = 0);
|
||||||
|
|
||||||
using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>;
|
using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>;
|
||||||
|
using BinaryMeasurementsRot3 = std::vector<BinaryMeasurement<Rot3>>;
|
||||||
|
|
||||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||||
inline boost::optional<IndexedPose> GTSAM_DEPRECATED
|
inline boost::optional<IndexedPose> GTSAM_DEPRECATED
|
||||||
|
|
|
||||||
|
|
@ -90,6 +90,22 @@ typedef gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Unified>,
|
||||||
gtsam::Point3>
|
gtsam::Point3>
|
||||||
GeneralSFMFactorCal3Unified;
|
GeneralSFMFactorCal3Unified;
|
||||||
|
|
||||||
|
typedef gtsam::GeneralSFMFactor<gtsam::PinholePose<gtsam::Cal3_S2>,
|
||||||
|
gtsam::Point3>
|
||||||
|
GeneralSFMFactorPoseCal3_S2;
|
||||||
|
typedef gtsam::GeneralSFMFactor<gtsam::PinholePose<gtsam::Cal3DS2>,
|
||||||
|
gtsam::Point3>
|
||||||
|
GeneralSFMFactorPoseCal3DS2;
|
||||||
|
typedef gtsam::GeneralSFMFactor<gtsam::PinholePose<gtsam::Cal3Bundler>,
|
||||||
|
gtsam::Point3>
|
||||||
|
GeneralSFMFactorPoseCal3Bundler;
|
||||||
|
typedef gtsam::GeneralSFMFactor<gtsam::PinholePose<gtsam::Cal3Fisheye>,
|
||||||
|
gtsam::Point3>
|
||||||
|
GeneralSFMFactorPoseCal3Fisheye;
|
||||||
|
typedef gtsam::GeneralSFMFactor<gtsam::PinholePose<gtsam::Cal3Unified>,
|
||||||
|
gtsam::Point3>
|
||||||
|
GeneralSFMFactorPoseCal3Unified;
|
||||||
|
|
||||||
template <CALIBRATION = {gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler,
|
template <CALIBRATION = {gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler,
|
||||||
gtsam::Cal3Fisheye, gtsam::Cal3Unified}>
|
gtsam::Cal3Fisheye, gtsam::Cal3Unified}>
|
||||||
virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor {
|
virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor {
|
||||||
|
|
|
||||||
|
|
@ -48,6 +48,7 @@ set(ignore
|
||||||
gtsam::Rot3Vector
|
gtsam::Rot3Vector
|
||||||
gtsam::KeyVector
|
gtsam::KeyVector
|
||||||
gtsam::BinaryMeasurementsUnit3
|
gtsam::BinaryMeasurementsUnit3
|
||||||
|
gtsam::BinaryMeasurementsRot3
|
||||||
gtsam::DiscreteKey
|
gtsam::DiscreteKey
|
||||||
gtsam::KeyPairDoubleMap)
|
gtsam::KeyPairDoubleMap)
|
||||||
|
|
||||||
|
|
@ -107,6 +108,14 @@ file(GLOB GTSAM_PYTHON_UTIL_FILES "${CMAKE_CURRENT_SOURCE_DIR}/gtsam/utils/*.py"
|
||||||
foreach(util_file ${GTSAM_PYTHON_UTIL_FILES})
|
foreach(util_file ${GTSAM_PYTHON_UTIL_FILES})
|
||||||
configure_file(${util_file} "${GTSAM_MODULE_PATH}/utils/${test_file}" COPYONLY)
|
configure_file(${util_file} "${GTSAM_MODULE_PATH}/utils/${test_file}" COPYONLY)
|
||||||
endforeach()
|
endforeach()
|
||||||
|
file(GLOB GTSAM_PYTHON_PREAMBLE_FILES "${CMAKE_CURRENT_SOURCE_DIR}/gtsam/preamble/*.h")
|
||||||
|
foreach(util_file ${GTSAM_PYTHON_PREAMBLE_FILES})
|
||||||
|
configure_file(${util_file} "${GTSAM_MODULE_PATH}/preamble/${test_file}" COPYONLY)
|
||||||
|
endforeach()
|
||||||
|
file(GLOB GTSAM_PYTHON_SPECIALIZATION_FILES "${CMAKE_CURRENT_SOURCE_DIR}/gtsam/specializations/*.h")
|
||||||
|
foreach(util_file ${GTSAM_PYTHON_SPECIALIZATION_FILES})
|
||||||
|
configure_file(${util_file} "${GTSAM_MODULE_PATH}/specializations/${test_file}" COPYONLY)
|
||||||
|
endforeach()
|
||||||
|
|
||||||
# Common directory for data/datasets stored with the package.
|
# Common directory for data/datasets stored with the package.
|
||||||
# This will store the data in the Python site package directly.
|
# This will store the data in the Python site package directly.
|
||||||
|
|
@ -129,6 +138,7 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON)
|
||||||
gtsam::KeyVector
|
gtsam::KeyVector
|
||||||
gtsam::FixedLagSmootherKeyTimestampMapValue
|
gtsam::FixedLagSmootherKeyTimestampMapValue
|
||||||
gtsam::BinaryMeasurementsUnit3
|
gtsam::BinaryMeasurementsUnit3
|
||||||
|
gtsam::BinaryMeasurementsRot3
|
||||||
gtsam::CameraSetCal3_S2
|
gtsam::CameraSetCal3_S2
|
||||||
gtsam::CameraSetCal3Bundler
|
gtsam::CameraSetCal3Bundler
|
||||||
gtsam::CameraSetCal3Unified
|
gtsam::CameraSetCal3Unified
|
||||||
|
|
|
||||||
|
|
@ -9,4 +9,18 @@
|
||||||
* automatic STL binding, such that the raw objects can be accessed in Python.
|
* automatic STL binding, such that the raw objects can be accessed in Python.
|
||||||
* Without this they will be automatically converted to a Python object, and all
|
* Without this they will be automatically converted to a Python object, and all
|
||||||
* mutations on Python side will not be reflected on C++.
|
* mutations on Python side will not be reflected on C++.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
// Including <stl.h> can cause some serious hard-to-debug bugs!!!
|
||||||
|
// #include <pybind11/stl.h>
|
||||||
|
#include <pybind11/stl_bind.h>
|
||||||
|
|
||||||
|
PYBIND11_MAKE_OPAQUE(
|
||||||
|
std::vector<gtsam::SfmTrack>);
|
||||||
|
|
||||||
|
PYBIND11_MAKE_OPAQUE(
|
||||||
|
std::vector<gtsam::SfmCamera>);
|
||||||
|
PYBIND11_MAKE_OPAQUE(
|
||||||
|
std::vector<gtsam::BinaryMeasurement<gtsam::Unit3>>);
|
||||||
|
PYBIND11_MAKE_OPAQUE(
|
||||||
|
std::vector<gtsam::BinaryMeasurement<gtsam::Rot3>>);
|
||||||
|
|
|
||||||
|
|
@ -13,4 +13,19 @@
|
||||||
|
|
||||||
py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(
|
py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(
|
||||||
m_, "BinaryMeasurementsUnit3");
|
m_, "BinaryMeasurementsUnit3");
|
||||||
|
py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Rot3> > >(
|
||||||
|
m_, "BinaryMeasurementsRot3");
|
||||||
py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap");
|
py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap");
|
||||||
|
|
||||||
|
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"
|
||||||
|
);
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue