Skip to content

Commit dfd50f9

Browse files
Extend python wrapper to include fisheye models.
Extend python wrapper to include fisheye camera models Cal3Fisheye and Cal3Unified.
1 parent cd3854a commit dfd50f9

File tree

1 file changed

+90
-12
lines changed

1 file changed

+90
-12
lines changed

gtsam/gtsam.i

Lines changed: 90 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -231,7 +231,7 @@ virtual class Value {
231231
};
232232

233233
#include <gtsam/base/GenericValue.h>
234-
template<T = {Vector, Matrix, gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::StereoPoint2, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::EssentialMatrix, gtsam::CalibratedCamera, gtsam::imuBias::ConstantBias}>
234+
template<T = {Vector, Matrix, gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::StereoPoint2, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::Cal3Fisheye, gtsam::Cal3Unified, gtsam::EssentialMatrix, gtsam::CalibratedCamera, gtsam::imuBias::ConstantBias}>
235235
virtual class GenericValue : gtsam::Value {
236236
void serializable() const;
237237
};
@@ -977,6 +977,52 @@ class Cal3Bundler {
977977
void pickle() const;
978978
};
979979

980+
#include <gtsam/geometry/Cal3Fisheye.h>
981+
class Cal3Fisheye {
982+
// Standard Constructors
983+
Cal3Fisheye();
984+
Cal3Fisheye(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4);
985+
Cal3Fisheye(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4, double tol);
986+
Cal3Fisheye(Vector v);
987+
988+
// Testable
989+
void print(string s = "Cal3Fisheye") const;
990+
bool equals(const gtsam::Cal3Fisheye& rhs, double tol) const;
991+
992+
// Manifold
993+
static size_t Dim();
994+
size_t dim() const;
995+
gtsam::Cal3Fisheye retract(Vector v) const;
996+
Vector localCoordinates(const gtsam::Cal3Fisheye& c) const;
997+
998+
// Action on Point2
999+
gtsam::Point2 calibrate(const gtsam::Point2& p) const;
1000+
gtsam::Point2 uncalibrate(const gtsam::Point2& p) const;
1001+
1002+
// Standard Interface
1003+
double fx() const;
1004+
double fy() const;
1005+
double skew() const;
1006+
double k1() const;
1007+
double k2() const;
1008+
double k3() const;
1009+
double k4() const;
1010+
double px() const;
1011+
double py() const;
1012+
gtsam::Point2 principalPoint() const;
1013+
Vector vector() const;
1014+
Vector k() const;
1015+
Matrix K() const;
1016+
Matrix inverse() const;
1017+
1018+
// enabling serialization functionality
1019+
void serialize() const;
1020+
1021+
// enable pickling in python
1022+
void pickle() const;
1023+
};
1024+
1025+
9801026
#include <gtsam/geometry/CalibratedCamera.h>
9811027
class CalibratedCamera {
9821028
// Standard Constructors and Named Constructors
@@ -1085,6 +1131,7 @@ typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
10851131
typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
10861132
typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
10871133
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
1134+
typedef gtsam::PinholeCamera<gtsam::Cal3Fisheye> PinholeCameraCal3Fisheye;
10881135

10891136
template<T>
10901137
class CameraSet {
@@ -1145,7 +1192,13 @@ gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3_S2& cameras,
11451192
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Bundler& cameras,
11461193
const gtsam::Point2Vector& measurements, double rank_tol,
11471194
bool optimize);
1148-
1195+
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Fisheye& cameras,
1196+
const gtsam::Point2Vector& measurements, double rank_tol,
1197+
bool optimize);
1198+
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Unified& cameras,
1199+
const gtsam::Point2Vector& measurements, double rank_tol,
1200+
bool optimize);
1201+
11491202
//*************************************************************************
11501203
// Symbolic
11511204
//*************************************************************************
@@ -2118,8 +2171,11 @@ class NonlinearFactorGraph {
21182171
template <T = {double, Vector, gtsam::Point2, gtsam::StereoPoint2,
21192172
gtsam::Point3, gtsam::Rot2, gtsam::SO3, gtsam::SO4,
21202173
gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,
2174+
gtsam::Cal3Fisheye, gtsam::Cal3Unified,
21212175
gtsam::CalibratedCamera, gtsam::PinholeCameraCal3_S2,
2122-
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
2176+
gtsam::PinholeCameraCal3Bundler,
2177+
gtsam::PinholeCameraCal3Fisheye,
2178+
gtsam::PinholeCameraCal3Unified,
21232179
gtsam::imuBias::ConstantBias}>
21242180
void addPrior(size_t key, const T& prior,
21252181
const gtsam::noiseModel::Base* noiseModel);
@@ -2252,9 +2308,13 @@ class Values {
22522308
void insert(size_t j, const gtsam::Cal3_S2& cal3_s2);
22532309
void insert(size_t j, const gtsam::Cal3DS2& cal3ds2);
22542310
void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler);
2311+
void insert(size_t j, const gtsam::Cal3Fisheye& cal3fisheye);
2312+
void insert(size_t j, const gtsam::Cal3Unified& cal3unified);
22552313
void insert(size_t j, const gtsam::EssentialMatrix& essential_matrix);
22562314
void insert(size_t j, const gtsam::PinholeCameraCal3_S2& simple_camera);
2257-
void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
2315+
void insert(size_t j, const gtsam::PinholeCameraCal3Bundler& camera);
2316+
void insert(size_t j, const gtsam::PinholeCameraCal3Fisheye& camera);
2317+
void insert(size_t j, const gtsam::PinholeCameraCal3Unified& camera);
22582318
void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
22592319
void insert(size_t j, const gtsam::NavState& nav_state);
22602320
void insert(size_t j, double c);
@@ -2272,9 +2332,13 @@ class Values {
22722332
void update(size_t j, const gtsam::Cal3_S2& cal3_s2);
22732333
void update(size_t j, const gtsam::Cal3DS2& cal3ds2);
22742334
void update(size_t j, const gtsam::Cal3Bundler& cal3bundler);
2335+
void update(size_t j, const gtsam::Cal3Fisheye& cal3fisheye);
2336+
void update(size_t j, const gtsam::Cal3Unified& cal3unified);
22752337
void update(size_t j, const gtsam::EssentialMatrix& essential_matrix);
22762338
void update(size_t j, const gtsam::PinholeCameraCal3_S2& simple_camera);
2277-
void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
2339+
void update(size_t j, const gtsam::PinholeCameraCal3Bundler& camera);
2340+
void update(size_t j, const gtsam::PinholeCameraCal3Fisheye& camera);
2341+
void update(size_t j, const gtsam::PinholeCameraCal3Unified& camera);
22782342
void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
22792343
void update(size_t j, const gtsam::NavState& nav_state);
22802344
void update(size_t j, Vector vector);
@@ -2294,10 +2358,14 @@ class Values {
22942358
gtsam::Cal3_S2,
22952359
gtsam::Cal3DS2,
22962360
gtsam::Cal3Bundler,
2297-
gtsam::EssentialMatrix,
2361+
gtsam::Cal3Fisheye,
2362+
gtsam::Cal3Unified,
2363+
gtsam::EssentialMatrix,
22982364
gtsam::PinholeCameraCal3_S2,
2299-
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
2300-
gtsam::imuBias::ConstantBias,
2365+
gtsam::PinholeCameraCal3Bundler,
2366+
gtsam::PinholeCameraCal3Fisheye,
2367+
gtsam::PinholeCameraCal3Unified,
2368+
gtsam::imuBias::ConstantBias,
23012369
gtsam::NavState,
23022370
Vector,
23032371
Matrix,
@@ -2603,7 +2671,9 @@ class ISAM2 {
26032671
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
26042672
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
26052673
gtsam::Cal3Bundler, gtsam::EssentialMatrix,
2606-
gtsam::PinholeCameraCal3_S2, gtsam::PinholeCamera<gtsam::Cal3Bundler>,
2674+
gtsam::PinholeCameraCal3_S2, gtsam::PinholeCameraCal3Bundler,
2675+
gtsam::Cal3Fisheye, gtsam::Cal3Unified,
2676+
gtsam::PinholeCameraCal3Fisheye, gtsam::PinholeCameraCal3Unified,
26072677
Vector, Matrix}>
26082678
VALUE calculateEstimate(size_t key) const;
26092679
gtsam::Values calculateBestEstimate() const;
@@ -2655,10 +2725,14 @@ template <T = {double,
26552725
gtsam::Cal3_S2,
26562726
gtsam::Cal3DS2,
26572727
gtsam::Cal3Bundler,
2728+
gtsam::Cal3Fisheye,
2729+
gtsam::Cal3Unified,
26582730
gtsam::CalibratedCamera,
26592731
gtsam::PinholeCameraCal3_S2,
26602732
gtsam::imuBias::ConstantBias,
2661-
gtsam::PinholeCamera<gtsam::Cal3Bundler>}>
2733+
gtsam::PinholeCameraCal3Bundler,
2734+
gtsam::PinholeCameraCal3Fisheye,
2735+
gtsam::PinholeCameraCal3Unified}>
26622736
virtual class PriorFactor : gtsam::NoiseModelFactor {
26632737
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
26642738
T prior() const;
@@ -2800,6 +2874,8 @@ virtual class GenericProjectionFactor : gtsam::NoiseModelFactor {
28002874
};
28012875
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> GenericProjectionFactorCal3_S2;
28022876
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> GenericProjectionFactorCal3DS2;
2877+
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3Fisheye> GenericProjectionFactorCal3Fisheye;
2878+
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3Unified> GenericProjectionFactorCal3Unified;
28032879

28042880

28052881
#include <gtsam/slam/GeneralSFMFactor.h>
@@ -2810,9 +2886,11 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor {
28102886
};
28112887
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2;
28122888
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
2813-
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3> GeneralSFMFactorCal3Bundler;
2889+
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3Bundler, gtsam::Point3> GeneralSFMFactorCal3Bundler;
2890+
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3Fisheye, gtsam::Point3> GeneralSFMFactorCal3Fisheye;
2891+
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3Unified, gtsam::Point3> GeneralSFMFactorCal3Unified;
28142892

2815-
template<CALIBRATION = {gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler}>
2893+
template<CALIBRATION = {gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::Cal3Fisheye, gtsam::Cal3Unified}>
28162894
virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor {
28172895
GeneralSFMFactor2(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t poseKey, size_t landmarkKey, size_t calibKey);
28182896
gtsam::Point2 measured() const;

0 commit comments

Comments
 (0)