Deprecate SimpleCamera properly
parent
e90bfdbf93
commit
e4c738dabf
|
@ -21,6 +21,7 @@
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||||
SimpleCamera simpleCamera(const Matrix34& P) {
|
SimpleCamera simpleCamera(const Matrix34& P) {
|
||||||
|
|
||||||
// P = [A|a] = s K cRw [I|-T], with s the unknown scale
|
// P = [A|a] = s K cRw [I|-T], with s the unknown scale
|
||||||
|
@ -45,5 +46,6 @@ namespace gtsam {
|
||||||
return SimpleCamera(Pose3(wRc, T),
|
return SimpleCamera(Pose3(wRc, T),
|
||||||
Cal3_S2(K(0, 0), K(1, 1), K(0, 1), K(0, 2), K(1, 2)));
|
Cal3_S2(K(0, 0), K(1, 1), K(0, 1), K(0, 2), K(1, 2)));
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,14 +19,23 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam/geometry/BearingRange.h>
|
#include <gtsam/geometry/BearingRange.h>
|
||||||
#include <gtsam/geometry/PinholeCamera.h>
|
#include <gtsam/geometry/Cal3Bundler.h>
|
||||||
|
#include <gtsam/geometry/Cal3DS2.h>
|
||||||
|
#include <gtsam/geometry/Cal3Unified.h>
|
||||||
#include <gtsam/geometry/Cal3_S2.h>
|
#include <gtsam/geometry/Cal3_S2.h>
|
||||||
|
#include <gtsam/geometry/PinholeCamera.h>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
/// A simple camera class with a Cal3_S2 calibration
|
/// Convenient aliases for Pinhole camera classes with different calibrations.
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
|
/// Also needed as forward declarations in the wrapper.
|
||||||
|
using PinholeCameraCal3_S2 = gtsam::PinholeCamera<gtsam::Cal3_S2>;
|
||||||
|
using PinholeCameraCal3Bundler = gtsam::PinholeCamera<gtsam::Cal3Bundler>;
|
||||||
|
//TODO Need to fix issue 621 for this to work with wrapper
|
||||||
|
// using PinholeCameraCal3DS2 = gtsam::PinholeCamera<gtsam::Cal3DS2>;
|
||||||
|
// using PinholeCameraCal3Unified = gtsam::PinholeCamera<gtsam::Cal3Unified>;
|
||||||
|
|
||||||
|
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||||
/**
|
/**
|
||||||
* @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x
|
* @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x
|
||||||
* Use PinholeCameraCal3_S2 instead
|
* Use PinholeCameraCal3_S2 instead
|
||||||
|
@ -140,4 +149,6 @@ struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {};
|
||||||
template <typename T>
|
template <typename T>
|
||||||
struct Range<SimpleCamera, T> : HasRange<SimpleCamera, T, double> {};
|
struct Range<SimpleCamera, T> : HasRange<SimpleCamera, T, double> {};
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
@ -329,7 +329,7 @@ virtual class Value {
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/base/GenericValue.h>
|
#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::SimpleCamera, 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::EssentialMatrix, gtsam::CalibratedCamera, gtsam::imuBias::ConstantBias}>
|
||||||
virtual class GenericValue : gtsam::Value {
|
virtual class GenericValue : gtsam::Value {
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
};
|
};
|
||||||
|
@ -1059,52 +1059,12 @@ class PinholeCamera {
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Forward declaration of PinholeCameraCalX is defined here.
|
||||||
#include <gtsam/geometry/SimpleCamera.h>
|
#include <gtsam/geometry/SimpleCamera.h>
|
||||||
virtual class SimpleCamera {
|
|
||||||
// Standard Constructors and Named Constructors
|
|
||||||
SimpleCamera();
|
|
||||||
SimpleCamera(const gtsam::Pose3& pose);
|
|
||||||
SimpleCamera(const gtsam::Pose3& pose, const gtsam::Cal3_S2& K);
|
|
||||||
static gtsam::SimpleCamera Level(const gtsam::Cal3_S2& K, const gtsam::Pose2& pose, double height);
|
|
||||||
static gtsam::SimpleCamera Level(const gtsam::Pose2& pose, double height);
|
|
||||||
static gtsam::SimpleCamera Lookat(const gtsam::Point3& eye, const gtsam::Point3& target,
|
|
||||||
const gtsam::Point3& upVector, const gtsam::Cal3_S2& K);
|
|
||||||
static gtsam::SimpleCamera Lookat(const gtsam::Point3& eye, const gtsam::Point3& target,
|
|
||||||
const gtsam::Point3& upVector);
|
|
||||||
|
|
||||||
// Testable
|
|
||||||
void print(string s) const;
|
|
||||||
bool equals(const gtsam::SimpleCamera& camera, double tol) const;
|
|
||||||
|
|
||||||
// Standard Interface
|
|
||||||
gtsam::Pose3 pose() const;
|
|
||||||
gtsam::Cal3_S2 calibration() const;
|
|
||||||
|
|
||||||
// Manifold
|
|
||||||
gtsam::SimpleCamera retract(Vector d) const;
|
|
||||||
Vector localCoordinates(const gtsam::SimpleCamera& 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::Point3 backproject(const gtsam::Point2& p, double depth) const;
|
|
||||||
double range(const gtsam::Point3& point);
|
|
||||||
double range(const gtsam::Pose3& pose);
|
|
||||||
|
|
||||||
// enabling serialization functionality
|
|
||||||
void serialize() const;
|
|
||||||
|
|
||||||
};
|
|
||||||
|
|
||||||
gtsam::SimpleCamera simpleCamera(const Matrix& P);
|
|
||||||
|
|
||||||
// Some typedefs for common camera types
|
// Some typedefs for common camera types
|
||||||
// PinholeCameraCal3_S2 is the same as SimpleCamera above
|
// PinholeCameraCal3_S2 is the same as SimpleCamera above
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
|
typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
|
||||||
//TODO (Issue 237) due to lack of jacobians of Cal3DS2_Base::calibrate, PinholeCamera does not apply to Cal3DS2/Unified
|
//TODO (Issue 621) due to lack of jacobians of Cal3DS2_Base::calibrate, PinholeCamera does not apply to Cal3DS2/Unified
|
||||||
//typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
|
//typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
|
||||||
//typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
|
//typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
|
||||||
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
|
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
|
||||||
|
@ -2069,7 +2029,7 @@ class NonlinearFactorGraph {
|
||||||
gtsam::KeySet keys() const;
|
gtsam::KeySet keys() const;
|
||||||
gtsam::KeyVector keyVector() const;
|
gtsam::KeyVector keyVector() const;
|
||||||
|
|
||||||
template<T = {Vector, gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::SO3, gtsam::SO4, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::PinholeCameraCal3_S2, gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::imuBias::ConstantBias}>
|
template<T = {Vector, gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::SO3, gtsam::SO4, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,gtsam::CalibratedCamera, gtsam::PinholeCameraCal3_S2, gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::imuBias::ConstantBias}>
|
||||||
void addPrior(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
|
void addPrior(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
|
||||||
|
|
||||||
// NonlinearFactorGraph
|
// NonlinearFactorGraph
|
||||||
|
@ -2493,7 +2453,7 @@ class ISAM2 {
|
||||||
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
|
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
|
||||||
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
|
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
|
||||||
gtsam::Cal3Bundler, gtsam::EssentialMatrix,
|
gtsam::Cal3Bundler, gtsam::EssentialMatrix,
|
||||||
gtsam::SimpleCamera, gtsam::PinholeCameraCal3_S2, gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
gtsam::PinholeCameraCal3_S2, gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
||||||
Vector, Matrix}>
|
Vector, Matrix}>
|
||||||
VALUE calculateEstimate(size_t key) const;
|
VALUE calculateEstimate(size_t key) const;
|
||||||
gtsam::Values calculateBestEstimate() const;
|
gtsam::Values calculateBestEstimate() const;
|
||||||
|
@ -2527,12 +2487,11 @@ class NonlinearISAM {
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// Nonlinear factor types
|
// Nonlinear factor types
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
#include <gtsam/geometry/SimpleCamera.h>
|
|
||||||
#include <gtsam/geometry/CalibratedCamera.h>
|
#include <gtsam/geometry/CalibratedCamera.h>
|
||||||
#include <gtsam/geometry/StereoPoint2.h>
|
#include <gtsam/geometry/StereoPoint2.h>
|
||||||
|
|
||||||
#include <gtsam/nonlinear/PriorFactor.h>
|
#include <gtsam/nonlinear/PriorFactor.h>
|
||||||
template<T = {Vector, gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Unit3, gtsam::Cal3_S2,gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::PinholeCameraCal3_S2, gtsam::imuBias::ConstantBias, gtsam::PinholeCamera<gtsam::Cal3Bundler>}>
|
template<T = {Vector, gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Unit3, gtsam::Cal3_S2,gtsam::CalibratedCamera, gtsam::PinholeCameraCal3_S2, gtsam::imuBias::ConstantBias, gtsam::PinholeCamera<gtsam::Cal3Bundler>}>
|
||||||
virtual class PriorFactor : gtsam::NoiseModelFactor {
|
virtual class PriorFactor : gtsam::NoiseModelFactor {
|
||||||
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
|
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
|
||||||
T prior() const;
|
T prior() const;
|
||||||
|
@ -2556,7 +2515,7 @@ virtual class BetweenFactor : gtsam::NoiseModelFactor {
|
||||||
template <T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
|
template <T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
|
||||||
gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2,
|
gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2,
|
||||||
gtsam::Pose3, gtsam::Cal3_S2, gtsam::CalibratedCamera,
|
gtsam::Pose3, gtsam::Cal3_S2, gtsam::CalibratedCamera,
|
||||||
gtsam::SimpleCamera, gtsam::PinholeCameraCal3_S2,
|
gtsam::PinholeCameraCal3_S2,
|
||||||
gtsam::imuBias::ConstantBias}>
|
gtsam::imuBias::ConstantBias}>
|
||||||
virtual class NonlinearEquality : gtsam::NoiseModelFactor {
|
virtual class NonlinearEquality : gtsam::NoiseModelFactor {
|
||||||
// Constructor - forces exact evaluation
|
// Constructor - forces exact evaluation
|
||||||
|
@ -2675,7 +2634,7 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor {
|
||||||
gtsam::Point2 measured() const;
|
gtsam::Point2 measured() const;
|
||||||
};
|
};
|
||||||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2;
|
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2;
|
||||||
//TODO (Issue 237) due to lack of jacobians of Cal3DS2_Base::calibrate, GeneralSFMFactor does not apply to Cal3DS2
|
//TODO (Issue 621) due to lack of jacobians of Cal3DS2_Base::calibrate, GeneralSFMFactor does not apply to Cal3DS2
|
||||||
//typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
|
//typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
|
||||||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3> GeneralSFMFactorCal3Bundler;
|
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3> GeneralSFMFactorCal3Bundler;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue