-
Notifications
You must be signed in to change notification settings - Fork 767
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Python fisheye interface #811
Changes from 7 commits
9967c59
dfd50f9
03e2744
73d40a5
55c1274
c8fc3cd
19e8cde
bdeb606
6205057
a411b66
66af007
0304992
d54e234
3118fde
0a73961
941594c
c595767
f53f5db
3402e46
17c37de
3e41ece
d130387
305521e
16cfc7f
c2bbe78
a115788
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -20,6 +20,8 @@ | |
|
||
#include <gtsam/geometry/Cal3_S2.h> | ||
#include <gtsam/geometry/Cal3Bundler.h> | ||
#include <gtsam/geometry/Cal3Fisheye.h> | ||
#include <gtsam/geometry/Cal3Unified.h> | ||
#include <gtsam/geometry/CameraSet.h> | ||
#include <gtsam/geometry/PinholeCamera.h> | ||
#include <gtsam/geometry/Pose2.h> | ||
|
@@ -499,6 +501,8 @@ TriangulationResult triangulateSafe(const CameraSet<CAMERA>& cameras, | |
// Vector of Cameras - used by the Python/MATLAB wrapper | ||
using CameraSetCal3Bundler = CameraSet<PinholeCamera<Cal3Bundler>>; | ||
using CameraSetCal3_S2 = CameraSet<PinholeCamera<Cal3_S2>>; | ||
using CameraSetCal3Fisheye = CameraSet<PinholeCamera<Cal3Fisheye>>; | ||
using CameraSetCal3Unified = CameraSet<PinholeCamera<Cal3Unified>>; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Similar question. Maybe we should pare down and only list here what's absolutely required in triangulation. Caller can include. |
||
|
||
} // \namespace gtsam | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -231,7 +231,7 @@ virtual class Value { | |
}; | ||
|
||
#include <gtsam/base/GenericValue.h> | ||
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}> | ||
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}> | ||
virtual class GenericValue : gtsam::Value { | ||
void serializable() const; | ||
}; | ||
|
@@ -977,6 +977,52 @@ class Cal3Bundler { | |
void pickle() const; | ||
}; | ||
|
||
#include <gtsam/geometry/Cal3Fisheye.h> | ||
class Cal3Fisheye { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. should this be a virtual class inheriting from a base class? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yeah this should technically inherit from |
||
// Standard Constructors | ||
Cal3Fisheye(); | ||
Cal3Fisheye(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4); | ||
Cal3Fisheye(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4, double tol); | ||
Cal3Fisheye(Vector v); | ||
|
||
// Testable | ||
void print(string s = "Cal3Fisheye") const; | ||
bool equals(const gtsam::Cal3Fisheye& rhs, double tol) const; | ||
|
||
// Manifold | ||
static size_t Dim(); | ||
size_t dim() const; | ||
gtsam::Cal3Fisheye retract(Vector v) const; | ||
Vector localCoordinates(const gtsam::Cal3Fisheye& c) const; | ||
|
||
// Action on Point2 | ||
gtsam::Point2 calibrate(const gtsam::Point2& p) const; | ||
gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; | ||
|
||
// Standard Interface | ||
double fx() const; | ||
double fy() const; | ||
double skew() const; | ||
double k1() const; | ||
double k2() const; | ||
double k3() const; | ||
double k4() const; | ||
double px() const; | ||
double py() const; | ||
gtsam::Point2 principalPoint() const; | ||
Vector vector() const; | ||
Vector k() const; | ||
Matrix K() const; | ||
Matrix inverse() const; | ||
|
||
// enabling serialization functionality | ||
void serialize() const; | ||
|
||
// enable pickling in python | ||
void pickle() const; | ||
}; | ||
|
||
|
||
#include <gtsam/geometry/CalibratedCamera.h> | ||
class CalibratedCamera { | ||
// Standard Constructors and Named Constructors | ||
|
@@ -1085,6 +1131,7 @@ 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> | ||
class CameraSet { | ||
|
@@ -1145,7 +1192,13 @@ gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3_S2& cameras, | |
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Bundler& cameras, | ||
const gtsam::Point2Vector& measurements, double rank_tol, | ||
bool optimize); | ||
|
||
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Fisheye& cameras, | ||
const gtsam::Point2Vector& measurements, double rank_tol, | ||
bool optimize); | ||
gtsam::Point3 triangulatePoint3(const gtsam::CameraSetCal3Unified& cameras, | ||
const gtsam::Point2Vector& measurements, double rank_tol, | ||
bool optimize); | ||
|
||
//************************************************************************* | ||
// Symbolic | ||
//************************************************************************* | ||
|
@@ -2118,8 +2171,11 @@ class NonlinearFactorGraph { | |
template <T = {double, Vector, gtsam::Point2, gtsam::StereoPoint2, | ||
gtsam::Point3, gtsam::Rot2, gtsam::SO3, gtsam::SO4, | ||
gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2, | ||
gtsam::Cal3Fisheye, gtsam::Cal3Unified, | ||
gtsam::CalibratedCamera, gtsam::PinholeCameraCal3_S2, | ||
gtsam::PinholeCamera<gtsam::Cal3Bundler>, | ||
gtsam::PinholeCameraCal3Bundler, | ||
gtsam::PinholeCameraCal3Fisheye, | ||
gtsam::PinholeCameraCal3Unified, | ||
gtsam::imuBias::ConstantBias}> | ||
void addPrior(size_t key, const T& prior, | ||
const gtsam::noiseModel::Base* noiseModel); | ||
|
@@ -2252,9 +2308,13 @@ class Values { | |
void insert(size_t j, const gtsam::Cal3_S2& cal3_s2); | ||
void insert(size_t j, const gtsam::Cal3DS2& cal3ds2); | ||
void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler); | ||
void insert(size_t j, const gtsam::Cal3Fisheye& cal3fisheye); | ||
void insert(size_t j, const gtsam::Cal3Unified& cal3unified); | ||
void insert(size_t j, const gtsam::EssentialMatrix& essential_matrix); | ||
void insert(size_t j, const gtsam::PinholeCameraCal3_S2& simple_camera); | ||
void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera); | ||
void insert(size_t j, const gtsam::PinholeCameraCal3Bundler& camera); | ||
void insert(size_t j, const gtsam::PinholeCameraCal3Fisheye& camera); | ||
void insert(size_t j, const gtsam::PinholeCameraCal3Unified& camera); | ||
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, double c); | ||
|
@@ -2272,9 +2332,13 @@ class Values { | |
void update(size_t j, const gtsam::Cal3_S2& cal3_s2); | ||
void update(size_t j, const gtsam::Cal3DS2& cal3ds2); | ||
void update(size_t j, const gtsam::Cal3Bundler& cal3bundler); | ||
void update(size_t j, const gtsam::Cal3Fisheye& cal3fisheye); | ||
void update(size_t j, const gtsam::Cal3Unified& cal3unified); | ||
void update(size_t j, const gtsam::EssentialMatrix& essential_matrix); | ||
void update(size_t j, const gtsam::PinholeCameraCal3_S2& simple_camera); | ||
void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera); | ||
void update(size_t j, const gtsam::PinholeCameraCal3Bundler& camera); | ||
void update(size_t j, const gtsam::PinholeCameraCal3Fisheye& camera); | ||
void update(size_t j, const gtsam::PinholeCameraCal3Unified& camera); | ||
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, Vector vector); | ||
|
@@ -2294,10 +2358,14 @@ class Values { | |
gtsam::Cal3_S2, | ||
gtsam::Cal3DS2, | ||
gtsam::Cal3Bundler, | ||
gtsam::EssentialMatrix, | ||
gtsam::Cal3Fisheye, | ||
gtsam::Cal3Unified, | ||
gtsam::EssentialMatrix, | ||
gtsam::PinholeCameraCal3_S2, | ||
gtsam::PinholeCamera<gtsam::Cal3Bundler>, | ||
gtsam::imuBias::ConstantBias, | ||
gtsam::PinholeCameraCal3Bundler, | ||
gtsam::PinholeCameraCal3Fisheye, | ||
gtsam::PinholeCameraCal3Unified, | ||
gtsam::imuBias::ConstantBias, | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Maybe make the formatting consistent? I was wondering what was going on here for a second. |
||
gtsam::NavState, | ||
Vector, | ||
Matrix, | ||
|
@@ -2603,7 +2671,9 @@ class ISAM2 { | |
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3, | ||
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, | ||
gtsam::Cal3Bundler, gtsam::EssentialMatrix, | ||
gtsam::PinholeCameraCal3_S2, gtsam::PinholeCamera<gtsam::Cal3Bundler>, | ||
gtsam::PinholeCameraCal3_S2, gtsam::PinholeCameraCal3Bundler, | ||
gtsam::Cal3Fisheye, gtsam::Cal3Unified, | ||
gtsam::PinholeCameraCal3Fisheye, gtsam::PinholeCameraCal3Unified, | ||
Vector, Matrix}> | ||
VALUE calculateEstimate(size_t key) const; | ||
gtsam::Values calculateBestEstimate() const; | ||
|
@@ -2655,10 +2725,14 @@ template <T = {double, | |
gtsam::Cal3_S2, | ||
gtsam::Cal3DS2, | ||
gtsam::Cal3Bundler, | ||
gtsam::Cal3Fisheye, | ||
gtsam::Cal3Unified, | ||
gtsam::CalibratedCamera, | ||
gtsam::PinholeCameraCal3_S2, | ||
gtsam::imuBias::ConstantBias, | ||
gtsam::PinholeCamera<gtsam::Cal3Bundler>}> | ||
gtsam::PinholeCameraCal3Bundler, | ||
gtsam::PinholeCameraCal3Fisheye, | ||
gtsam::PinholeCameraCal3Unified}> | ||
virtual class PriorFactor : gtsam::NoiseModelFactor { | ||
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); | ||
T prior() const; | ||
|
@@ -2800,6 +2874,8 @@ virtual class GenericProjectionFactor : gtsam::NoiseModelFactor { | |
}; | ||
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> GenericProjectionFactorCal3_S2; | ||
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> GenericProjectionFactorCal3DS2; | ||
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3Fisheye> GenericProjectionFactorCal3Fisheye; | ||
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3Unified> GenericProjectionFactorCal3Unified; | ||
|
||
|
||
#include <gtsam/slam/GeneralSFMFactor.h> | ||
|
@@ -2810,9 +2886,11 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { | |
}; | ||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2; | ||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2; | ||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3> GeneralSFMFactorCal3Bundler; | ||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3Bundler, gtsam::Point3> GeneralSFMFactorCal3Bundler; | ||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3Fisheye, gtsam::Point3> GeneralSFMFactorCal3Fisheye; | ||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3Unified, gtsam::Point3> GeneralSFMFactorCal3Unified; | ||
|
||
template<CALIBRATION = {gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler}> | ||
template<CALIBRATION = {gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::Cal3Fisheye, gtsam::Cal3Unified}> | ||
virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { | ||
GeneralSFMFactor2(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t poseKey, size_t landmarkKey, size_t calibKey); | ||
gtsam::Point2 measured() const; | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,105 @@ | ||
""" | ||
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, | ||
Atlanta, Georgia 30332-0415 | ||
All Rights Reserved | ||
|
||
See LICENSE for the license information | ||
|
||
Cal3Unified unit tests. | ||
Author: Frank Dellaert & Duy Nguyen Ta (Python) | ||
""" | ||
import unittest | ||
|
||
import numpy as np | ||
|
||
import gtsam | ||
from gtsam.utils.test_case import GtsamTestCase | ||
|
||
|
||
class TestCal3Fisheye(GtsamTestCase): | ||
|
||
def test_Cal3Fisheye(self): | ||
K = gtsam.Cal3Fisheye() | ||
self.assertEqual(K.fx(), 1.) | ||
self.assertEqual(K.fy(), 1.) | ||
|
||
def test_distortion(self): | ||
"Equidistant fisheye model of focal length f, defined as r/f = tan(theta)" | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Make this into triple-quote doctsring? |
||
equidistant = gtsam.Cal3Fisheye() | ||
x, y, z = 1, 0, 1 | ||
u, v = equidistant.uncalibrate([x, y]) | ||
x2, y2 = equidistant.calibrate([u, v]) | ||
self.assertAlmostEqual(u, np.arctan2(x, z)) | ||
self.assertAlmostEqual(v, 0) | ||
self.assertAlmostEqual(x2, x) | ||
self.assertAlmostEqual(y2, 0) | ||
|
||
def test_pinhole(self): | ||
"Spatial equidistant camera projection" | ||
x, y, z = 1.0, 0.0, 1.0 | ||
u, v = np.arctan2(x, z), 0.0 | ||
camera = gtsam.PinholeCameraCal3Fisheye() | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. A lot of the review comments also apply here. Please ask for another round of reviews after updating these. 🙂 |
||
|
||
pt1 = camera.Project([x, y, z]) | ||
self.gtsamAssertEquals(pt1, np.array([x/z, y/z])) | ||
|
||
pt2 = camera.project([x, y, z]) | ||
self.gtsamAssertEquals(pt2, np.array([u, v])) | ||
|
||
obj1 = camera.backproject([u, v], z) | ||
self.gtsamAssertEquals(obj1, np.array([x, y, z])) | ||
|
||
r1 = camera.range(np.array([x, y, z])) | ||
self.assertEqual(r1, np.linalg.norm([x, y, z])) | ||
|
||
def test_generic_factor(self): | ||
"Evaluate residual using pose and point as state variables" | ||
objPoint = np.array([1, 0, 1]) | ||
imgPoint = np.array([np.arctan2(objPoint[0], objPoint[2]), 0]) | ||
graph = gtsam.NonlinearFactorGraph() | ||
state = gtsam.Values() | ||
measured = imgPoint | ||
noiseModel = gtsam.noiseModel.Isotropic.Sigma(2, 1) | ||
poseKey = gtsam.symbol_shorthand.P(0) | ||
pointKey = gtsam.symbol_shorthand.L(0) | ||
k = gtsam.Cal3Fisheye() | ||
state.insert_pose3(poseKey, gtsam.Pose3()) | ||
state.insert_point3(pointKey, gtsam.Point3(objPoint)) | ||
factor = gtsam.GenericProjectionFactorCal3Fisheye(measured, noiseModel, poseKey, pointKey, k) | ||
graph.add(factor) | ||
score = graph.error(state) | ||
self.assertAlmostEqual(score, 0) | ||
|
||
def test_sfm_factor2(self): | ||
"Evaluate residual with camera, pose and point as state variables" | ||
objPoint = np.array([1, 0, 1]) | ||
imgPoint = np.array([np.arctan2(objPoint[0], objPoint[2]), 0]) | ||
graph = gtsam.NonlinearFactorGraph() | ||
state = gtsam.Values() | ||
measured = imgPoint | ||
noiseModel = gtsam.noiseModel.Isotropic.Sigma(2, 1) | ||
cameraKey = gtsam.symbol_shorthand.K(0) | ||
poseKey = gtsam.symbol_shorthand.P(0) | ||
landmarkKey = gtsam.symbol_shorthand.L(0) | ||
k = gtsam.Cal3Fisheye() | ||
state.insert_cal3fisheye(cameraKey, k) | ||
state.insert_pose3(poseKey, gtsam.Pose3()) | ||
state.insert_point3(landmarkKey, gtsam.Point3(objPoint)) | ||
factor = gtsam.GeneralSFMFactor2Cal3Fisheye(measured, noiseModel, poseKey, landmarkKey, cameraKey) | ||
graph.add(factor) | ||
score = graph.error(state) | ||
self.assertAlmostEqual(score, 0) | ||
|
||
def test_retract(self): | ||
expected = gtsam.Cal3Fisheye(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6, | ||
1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10) | ||
K = gtsam.Cal3Fisheye(100, 105, 0.0, 320, 240, | ||
1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3) | ||
d = np.array([2, 3, 4, 5, 6, 7, 8, 9, 10], order='F') | ||
actual = K.retract(d) | ||
self.gtsamAssertEquals(actual, expected) | ||
np.testing.assert_allclose(d, K.localCoordinates(actual)) | ||
|
||
|
||
if __name__ == "__main__": | ||
unittest.main() |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Hmmm. why do we even have these typedefs and includes here? Seems like it exacerbates header bloat/compile times.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
My guess is that it is an artifact of before we understood the wrapper's behavior really well. The wrapper has seen some nice improvements in the past year so we may as well kill this, while moving the typedef for
Cal3_S2
inside the deprecation block.