Merge branch 'develop' into fix/621
commit
0b81b763a2
|
@ -21,6 +21,7 @@
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
SimpleCamera simpleCamera(const Matrix34& P) {
|
||||
|
||||
// P = [A|a] = s K cRw [I|-T], with s the unknown scale
|
||||
|
@ -45,5 +46,6 @@ namespace gtsam {
|
|||
return SimpleCamera(Pose3(wRc, T),
|
||||
Cal3_S2(K(0, 0), K(1, 1), K(0, 1), K(0, 2), K(1, 2)));
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
|
|
|
@ -19,14 +19,23 @@
|
|||
#pragma once
|
||||
|
||||
#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/PinholeCamera.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/// A simple camera class with a Cal3_S2 calibration
|
||||
typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
|
||||
/// Convenient aliases for Pinhole camera classes with different calibrations.
|
||||
/// 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
|
||||
* Use PinholeCameraCal3_S2 instead
|
||||
|
@ -140,4 +149,6 @@ struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {};
|
|||
template <typename T>
|
||||
struct Range<SimpleCamera, T> : HasRange<SimpleCamera, T, double> {};
|
||||
|
||||
#endif
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -26,6 +26,8 @@
|
|||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
|
||||
static const Cal3_S2 K(625, 625, 0, 0, 0);
|
||||
|
||||
static const Pose3 pose1(Rot3(Vector3(1, -1, -1).asDiagonal()),
|
||||
|
@ -149,6 +151,8 @@ TEST( SimpleCamera, simpleCamera)
|
|||
CHECK(assert_equal(expected, actual,1e-1));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -329,7 +329,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::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 {
|
||||
void serializable() const;
|
||||
};
|
||||
|
@ -1059,52 +1059,12 @@ class PinholeCamera {
|
|||
void serialize() const;
|
||||
};
|
||||
|
||||
// Forward declaration of PinholeCameraCalX is defined here.
|
||||
#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
|
||||
// PinholeCameraCal3_S2 is the same as SimpleCamera above
|
||||
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::Cal3Unified> PinholeCameraCal3Unified;
|
||||
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
|
||||
|
@ -1150,7 +1110,7 @@ gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
|||
gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
||||
gtsam::Cal3Bundler* sharedCal, const gtsam::Point2Vector& measurements,
|
||||
double rank_tol, bool optimize);
|
||||
|
||||
|
||||
//*************************************************************************
|
||||
// Symbolic
|
||||
//*************************************************************************
|
||||
|
@ -2069,7 +2029,7 @@ class NonlinearFactorGraph {
|
|||
gtsam::KeySet keys() 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);
|
||||
|
||||
// NonlinearFactorGraph
|
||||
|
@ -2493,7 +2453,7 @@ 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::SimpleCamera, gtsam::PinholeCameraCal3_S2, gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
||||
gtsam::PinholeCameraCal3_S2, gtsam::PinholeCamera<gtsam::Cal3Bundler>,
|
||||
Vector, Matrix}>
|
||||
VALUE calculateEstimate(size_t key) const;
|
||||
gtsam::Values calculateBestEstimate() const;
|
||||
|
@ -2527,12 +2487,11 @@ class NonlinearISAM {
|
|||
//*************************************************************************
|
||||
// Nonlinear factor types
|
||||
//*************************************************************************
|
||||
#include <gtsam/geometry/SimpleCamera.h>
|
||||
#include <gtsam/geometry/CalibratedCamera.h>
|
||||
#include <gtsam/geometry/StereoPoint2.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 {
|
||||
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
|
||||
T prior() const;
|
||||
|
@ -2556,7 +2515,7 @@ virtual class BetweenFactor : gtsam::NoiseModelFactor {
|
|||
template <T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
|
||||
gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2,
|
||||
gtsam::Pose3, gtsam::Cal3_S2, gtsam::CalibratedCamera,
|
||||
gtsam::SimpleCamera, gtsam::PinholeCameraCal3_S2,
|
||||
gtsam::PinholeCameraCal3_S2,
|
||||
gtsam::imuBias::ConstantBias}>
|
||||
virtual class NonlinearEquality : gtsam::NoiseModelFactor {
|
||||
// Constructor - forces exact evaluation
|
||||
|
@ -2675,7 +2634,7 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor {
|
|||
gtsam::Point2 measured() const;
|
||||
};
|
||||
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::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3> GeneralSFMFactorCal3Bundler;
|
||||
|
||||
|
|
|
@ -43,7 +43,6 @@ typedef PriorFactor<Pose3> PriorFactorPose3;
|
|||
typedef PriorFactor<Cal3_S2> PriorFactorCal3_S2;
|
||||
typedef PriorFactor<Cal3DS2> PriorFactorCal3DS2;
|
||||
typedef PriorFactor<CalibratedCamera> PriorFactorCalibratedCamera;
|
||||
typedef PriorFactor<SimpleCamera> PriorFactorSimpleCamera;
|
||||
typedef PriorFactor<PinholeCameraCal3_S2> PriorFactorPinholeCameraCal3_S2;
|
||||
typedef PriorFactor<StereoCamera> PriorFactorStereoCamera;
|
||||
|
||||
|
@ -68,7 +67,6 @@ typedef NonlinearEquality<Pose3> NonlinearEqualityPose3;
|
|||
typedef NonlinearEquality<Cal3_S2> NonlinearEqualityCal3_S2;
|
||||
typedef NonlinearEquality<Cal3DS2> NonlinearEqualityCal3DS2;
|
||||
typedef NonlinearEquality<CalibratedCamera> NonlinearEqualityCalibratedCamera;
|
||||
typedef NonlinearEquality<SimpleCamera> NonlinearEqualitySimpleCamera;
|
||||
typedef NonlinearEquality<PinholeCameraCal3_S2> NonlinearEqualityPinholeCameraCal3_S2;
|
||||
typedef NonlinearEquality<StereoCamera> NonlinearEqualityStereoCamera;
|
||||
|
||||
|
@ -77,10 +75,8 @@ typedef RangeFactor<Pose3, Point3> RangeFactor3D;
|
|||
typedef RangeFactor<Pose2, Pose2> RangeFactorPose2;
|
||||
typedef RangeFactor<Pose3, Pose3> RangeFactorPose3;
|
||||
typedef RangeFactor<CalibratedCamera, Point3> RangeFactorCalibratedCameraPoint;
|
||||
typedef RangeFactor<SimpleCamera, Point3> RangeFactorSimpleCameraPoint;
|
||||
typedef RangeFactor<PinholeCameraCal3_S2, Point3> RangeFactorPinholeCameraCal3_S2Point;
|
||||
typedef RangeFactor<CalibratedCamera, CalibratedCamera> RangeFactorCalibratedCamera;
|
||||
typedef RangeFactor<SimpleCamera, SimpleCamera> RangeFactorSimpleCamera;
|
||||
typedef RangeFactor<PinholeCameraCal3_S2, PinholeCameraCal3_S2> RangeFactorPinholeCameraCal3_S2;
|
||||
|
||||
typedef BearingRangeFactor<Pose2, Point2> BearingRangeFactor2D;
|
||||
|
@ -90,6 +86,7 @@ typedef GenericProjectionFactor<Pose3, Point3, Cal3_S2> GenericProjectionFactorC
|
|||
typedef GenericProjectionFactor<Pose3, Point3, Cal3DS2> GenericProjectionFactorCal3DS2;
|
||||
|
||||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2;
|
||||
//TODO fix issue 621
|
||||
//typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
|
||||
|
||||
typedef gtsam::GeneralSFMFactor2<gtsam::Cal3_S2> GeneralSFMFactor2Cal3_S2;
|
||||
|
@ -129,7 +126,6 @@ GTSAM_VALUE_EXPORT(gtsam::Cal3_S2);
|
|||
GTSAM_VALUE_EXPORT(gtsam::Cal3DS2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2Stereo);
|
||||
GTSAM_VALUE_EXPORT(gtsam::CalibratedCamera);
|
||||
GTSAM_VALUE_EXPORT(gtsam::SimpleCamera);
|
||||
GTSAM_VALUE_EXPORT(gtsam::PinholeCameraCal3_S2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::StereoCamera);
|
||||
|
||||
|
@ -150,7 +146,6 @@ BOOST_CLASS_EXPORT_GUID(PriorFactorPose3, "gtsam::PriorFactorPose3");
|
|||
BOOST_CLASS_EXPORT_GUID(PriorFactorCal3_S2, "gtsam::PriorFactorCal3_S2");
|
||||
BOOST_CLASS_EXPORT_GUID(PriorFactorCal3DS2, "gtsam::PriorFactorCal3DS2");
|
||||
BOOST_CLASS_EXPORT_GUID(PriorFactorCalibratedCamera, "gtsam::PriorFactorCalibratedCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(PriorFactorSimpleCamera, "gtsam::PriorFactorSimpleCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(PriorFactorStereoCamera, "gtsam::PriorFactorStereoCamera");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(BetweenFactorLieVector, "gtsam::BetweenFactorLieVector");
|
||||
|
@ -174,7 +169,6 @@ BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose3, "gtsam::NonlinearEqualityPose3")
|
|||
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3_S2, "gtsam::NonlinearEqualityCal3_S2");
|
||||
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3DS2, "gtsam::NonlinearEqualityCal3DS2");
|
||||
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCalibratedCamera, "gtsam::NonlinearEqualityCalibratedCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(NonlinearEqualitySimpleCamera, "gtsam::NonlinearEqualitySimpleCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoCamera, "gtsam::NonlinearEqualityStereoCamera");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactor2D, "gtsam::RangeFactor2D");
|
||||
|
@ -182,9 +176,7 @@ BOOST_CLASS_EXPORT_GUID(RangeFactor3D, "gtsam::RangeFactor3D");
|
|||
BOOST_CLASS_EXPORT_GUID(RangeFactorPose2, "gtsam::RangeFactorPose2");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorPose3, "gtsam::RangeFactorPose3");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCameraPoint, "gtsam::RangeFactorCalibratedCameraPoint");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleCameraPoint");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D");
|
||||
|
||||
|
@ -192,12 +184,29 @@ BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectio
|
|||
BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2");
|
||||
//TODO Fix issue 621
|
||||
//BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D");
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
|
||||
typedef PriorFactor<SimpleCamera> PriorFactorSimpleCamera;
|
||||
typedef NonlinearEquality<SimpleCamera> NonlinearEqualitySimpleCamera;
|
||||
typedef RangeFactor<SimpleCamera, Point3> RangeFactorSimpleCameraPoint;
|
||||
typedef RangeFactor<SimpleCamera, SimpleCamera> RangeFactorSimpleCamera;
|
||||
|
||||
GTSAM_VALUE_EXPORT(gtsam::SimpleCamera);
|
||||
BOOST_CLASS_EXPORT_GUID(PriorFactorSimpleCamera, "gtsam::PriorFactorSimpleCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(NonlinearEqualitySimpleCamera, "gtsam::NonlinearEqualitySimpleCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleCameraPoint");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera");
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Actual implementations of functions
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -14,11 +14,12 @@ import unittest
|
|||
import numpy as np
|
||||
|
||||
import gtsam
|
||||
from gtsam import Cal3_S2, Point3, Pose2, Pose3, Rot3, SimpleCamera
|
||||
from gtsam import Cal3_S2, Point3, Pose2, Pose3, Rot3, PinholeCameraCal3_S2 as SimpleCamera
|
||||
from gtsam.utils.test_case import GtsamTestCase
|
||||
|
||||
K = Cal3_S2(625, 625, 0, 0, 0)
|
||||
|
||||
|
||||
class TestSimpleCamera(GtsamTestCase):
|
||||
|
||||
def test_constructor(self):
|
||||
|
@ -29,15 +30,15 @@ class TestSimpleCamera(GtsamTestCase):
|
|||
|
||||
def test_level2(self):
|
||||
# Create a level camera, looking in Y-direction
|
||||
pose2 = Pose2(0.4,0.3,math.pi/2.0)
|
||||
pose2 = Pose2(0.4, 0.3, math.pi/2.0)
|
||||
camera = SimpleCamera.Level(K, pose2, 0.1)
|
||||
|
||||
# expected
|
||||
x = Point3(1,0,0)
|
||||
y = Point3(0,0,-1)
|
||||
z = Point3(0,1,0)
|
||||
wRc = Rot3(x,y,z)
|
||||
expected = Pose3(wRc,Point3(0.4,0.3,0.1))
|
||||
x = Point3(1, 0, 0)
|
||||
y = Point3(0, 0, -1)
|
||||
z = Point3(0, 1, 0)
|
||||
wRc = Rot3(x, y, z)
|
||||
expected = Pose3(wRc, Point3(0.4, 0.3, 0.1))
|
||||
self.gtsamAssertEquals(camera.pose(), expected, 1e-9)
|
||||
|
||||
|
||||
|
|
|
@ -89,10 +89,8 @@ typedef RangeFactor<Pose3, Point3> RangeFactor3D;
|
|||
typedef RangeFactor<Pose2, Pose2> RangeFactorPose2;
|
||||
typedef RangeFactor<Pose3, Pose3> RangeFactorPose3;
|
||||
typedef RangeFactor<CalibratedCamera, Point3> RangeFactorCalibratedCameraPoint;
|
||||
typedef RangeFactor<SimpleCamera, Point3> RangeFactorSimpleCameraPoint;
|
||||
typedef RangeFactor<PinholeCameraCal3_S2, Point3> RangeFactorPinholeCameraCal3_S2Point;
|
||||
typedef RangeFactor<CalibratedCamera, CalibratedCamera> RangeFactorCalibratedCamera;
|
||||
typedef RangeFactor<SimpleCamera, SimpleCamera> RangeFactorSimpleCamera;
|
||||
typedef RangeFactor<PinholeCameraCal3_S2, PinholeCameraCal3_S2> RangeFactorPinholeCameraCal3_S2;
|
||||
|
||||
typedef BearingRangeFactor<Pose2, Point2> BearingRangeFactor2D;
|
||||
|
@ -102,6 +100,7 @@ typedef GenericProjectionFactor<Pose3, Point3, Cal3_S2> GenericProjectionFactorC
|
|||
typedef GenericProjectionFactor<Pose3, Point3, Cal3DS2> GenericProjectionFactorCal3DS2;
|
||||
|
||||
typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2;
|
||||
//TODO Fix issue 621 for this to work
|
||||
//typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
|
||||
|
||||
typedef gtsam::GeneralSFMFactor2<gtsam::Cal3_S2> GeneralSFMFactor2Cal3_S2;
|
||||
|
@ -145,7 +144,6 @@ GTSAM_VALUE_EXPORT(gtsam::Cal3_S2);
|
|||
GTSAM_VALUE_EXPORT(gtsam::Cal3DS2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2Stereo);
|
||||
GTSAM_VALUE_EXPORT(gtsam::CalibratedCamera);
|
||||
GTSAM_VALUE_EXPORT(gtsam::SimpleCamera);
|
||||
GTSAM_VALUE_EXPORT(gtsam::PinholeCameraCal3_S2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::StereoCamera);
|
||||
|
||||
|
@ -190,9 +188,9 @@ BOOST_CLASS_EXPORT_GUID(RangeFactor3D, "gtsam::RangeFactor3D");
|
|||
BOOST_CLASS_EXPORT_GUID(RangeFactorPose2, "gtsam::RangeFactorPose2");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorPose3, "gtsam::RangeFactorPose3");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCameraPoint, "gtsam::RangeFactorCalibratedCameraPoint");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleCameraPoint");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorPinholeCameraCal3_S2Point, "gtsam::RangeFactorPinholeCameraCal3_S2Point");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera");
|
||||
BOOST_CLASS_EXPORT_GUID(RangeFactorPinholeCameraCal3_S2, "gtsam::RangeFactorPinholeCameraCal3_S2");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D");
|
||||
|
||||
|
@ -200,6 +198,7 @@ BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectio
|
|||
BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2");
|
||||
//TODO fix issue 621
|
||||
//BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2");
|
||||
|
||||
BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2");
|
||||
|
@ -352,9 +351,9 @@ TEST (testSerializationSLAM, factors) {
|
|||
RangeFactorPose2 rangeFactorPose2(a08, b08, 2.0, model1);
|
||||
RangeFactorPose3 rangeFactorPose3(a09, b09, 2.0, model1);
|
||||
RangeFactorCalibratedCameraPoint rangeFactorCalibratedCameraPoint(a12, a05, 2.0, model1);
|
||||
RangeFactorSimpleCameraPoint rangeFactorSimpleCameraPoint(a13, a05, 2.0, model1);
|
||||
RangeFactorPinholeCameraCal3_S2Point rangeFactorPinholeCameraCal3_S2Point(a13, a05, 2.0, model1);
|
||||
RangeFactorCalibratedCamera rangeFactorCalibratedCamera(a12, b12, 2.0, model1);
|
||||
RangeFactorSimpleCamera rangeFactorSimpleCamera(a13, b13, 2.0, model1);
|
||||
RangeFactorPinholeCameraCal3_S2 rangeFactorPinholeCameraCal3_S2(a13, b13, 2.0, model1);
|
||||
|
||||
BearingRangeFactor2D bearingRangeFactor2D(a08, a03, rot2, 2.0, model2);
|
||||
|
||||
|
@ -405,9 +404,9 @@ TEST (testSerializationSLAM, factors) {
|
|||
graph += rangeFactorPose2;
|
||||
graph += rangeFactorPose3;
|
||||
graph += rangeFactorCalibratedCameraPoint;
|
||||
graph += rangeFactorSimpleCameraPoint;
|
||||
graph += rangeFactorPinholeCameraCal3_S2Point;
|
||||
graph += rangeFactorCalibratedCamera;
|
||||
graph += rangeFactorSimpleCamera;
|
||||
graph += rangeFactorPinholeCameraCal3_S2;
|
||||
|
||||
graph += bearingRangeFactor2D;
|
||||
|
||||
|
@ -463,9 +462,9 @@ TEST (testSerializationSLAM, factors) {
|
|||
EXPECT(equalsObj<RangeFactorPose2>(rangeFactorPose2));
|
||||
EXPECT(equalsObj<RangeFactorPose3>(rangeFactorPose3));
|
||||
EXPECT(equalsObj<RangeFactorCalibratedCameraPoint>(rangeFactorCalibratedCameraPoint));
|
||||
EXPECT(equalsObj<RangeFactorSimpleCameraPoint>(rangeFactorSimpleCameraPoint));
|
||||
EXPECT(equalsObj<RangeFactorPinholeCameraCal3_S2Point>(rangeFactorPinholeCameraCal3_S2Point));
|
||||
EXPECT(equalsObj<RangeFactorCalibratedCamera>(rangeFactorCalibratedCamera));
|
||||
EXPECT(equalsObj<RangeFactorSimpleCamera>(rangeFactorSimpleCamera));
|
||||
EXPECT(equalsObj<RangeFactorPinholeCameraCal3_S2>(rangeFactorPinholeCameraCal3_S2));
|
||||
|
||||
EXPECT(equalsObj<BearingRangeFactor2D>(bearingRangeFactor2D));
|
||||
|
||||
|
@ -521,9 +520,9 @@ TEST (testSerializationSLAM, factors) {
|
|||
EXPECT(equalsXML<RangeFactorPose2>(rangeFactorPose2));
|
||||
EXPECT(equalsXML<RangeFactorPose3>(rangeFactorPose3));
|
||||
EXPECT(equalsXML<RangeFactorCalibratedCameraPoint>(rangeFactorCalibratedCameraPoint));
|
||||
EXPECT(equalsXML<RangeFactorSimpleCameraPoint>(rangeFactorSimpleCameraPoint));
|
||||
EXPECT(equalsXML<RangeFactorPinholeCameraCal3_S2Point>(rangeFactorPinholeCameraCal3_S2Point));
|
||||
EXPECT(equalsXML<RangeFactorCalibratedCamera>(rangeFactorCalibratedCamera));
|
||||
EXPECT(equalsXML<RangeFactorSimpleCamera>(rangeFactorSimpleCamera));
|
||||
EXPECT(equalsXML<RangeFactorPinholeCameraCal3_S2>(rangeFactorPinholeCameraCal3_S2));
|
||||
|
||||
EXPECT(equalsXML<BearingRangeFactor2D>(bearingRangeFactor2D));
|
||||
|
||||
|
@ -579,9 +578,9 @@ TEST (testSerializationSLAM, factors) {
|
|||
EXPECT(equalsBinary<RangeFactorPose2>(rangeFactorPose2));
|
||||
EXPECT(equalsBinary<RangeFactorPose3>(rangeFactorPose3));
|
||||
EXPECT(equalsBinary<RangeFactorCalibratedCameraPoint>(rangeFactorCalibratedCameraPoint));
|
||||
EXPECT(equalsBinary<RangeFactorSimpleCameraPoint>(rangeFactorSimpleCameraPoint));
|
||||
EXPECT(equalsBinary<RangeFactorPinholeCameraCal3_S2Point>(rangeFactorPinholeCameraCal3_S2Point));
|
||||
EXPECT(equalsBinary<RangeFactorCalibratedCamera>(rangeFactorCalibratedCamera));
|
||||
EXPECT(equalsBinary<RangeFactorSimpleCamera>(rangeFactorSimpleCamera));
|
||||
EXPECT(equalsBinary<RangeFactorPinholeCameraCal3_S2>(rangeFactorPinholeCameraCal3_S2));
|
||||
|
||||
EXPECT(equalsBinary<BearingRangeFactor2D>(bearingRangeFactor2D));
|
||||
|
||||
|
|
Loading…
Reference in New Issue