testInvDepthFactorVariant3.cpp
Go to the documentation of this file.
1 /*
2  * testInvDepthFactorVariant3.cpp
3  *
4  * Created on: Apr 13, 2012
5  * Author: cbeall3
6  */
7 
13 #include <gtsam/inference/Symbol.h>
15 #include <gtsam/geometry/Cal3_S2.h>
16 #include <gtsam/geometry/Pose3.h>
17 #include <gtsam/geometry/Point3.h>
18 #include <gtsam/geometry/Point2.h>
19 
20 using namespace std;
21 using namespace gtsam;
22 
23 /* ************************************************************************* */
24 TEST( InvDepthFactorVariant3, optimize) {
25 
26  // Create two poses looking in the x-direction
27  Pose3 pose1(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0));
28  Pose3 pose2(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5));
29 
30  // Create a landmark 5 meters in front of pose1 (camera center at (0,0,1))
31  Point3 landmark(5, 0, 1);
32 
33  // Create image observations
34  Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480));
37  Point2 pixel1 = camera1.project(landmark);
38  Point2 pixel2 = camera2.project(landmark);
39 
40  // Create expected landmark
41  Point3 landmark_p1 = pose1.transformTo(landmark);
42  // landmark_p1.print("Landmark in Pose1 Frame:\n");
43  double theta = atan2(landmark_p1.x(), landmark_p1.z());
44  double phi = atan2(landmark_p1.y(), sqrt(landmark_p1.x()*landmark_p1.x()+landmark_p1.z()*landmark_p1.z()));
45  double rho = 1./landmark_p1.norm();
46  Vector3 expected((Vector(3) << theta, phi, rho).finished());
47 
48 
49 
50  // Create a factor graph with two inverse depth factors and two pose priors
51  Key poseKey1(1);
52  Key poseKey2(2);
53  Key landmarkKey(100);
54  SharedNoiseModel sigma(noiseModel::Unit::Create(2));
58  NonlinearFactor::shared_ptr factor4(new InvDepthFactorVariant3b(poseKey1, poseKey2, landmarkKey, pixel2, K, sigma));
63  graph.push_back(factor4);
64 
65  // Create a values with slightly incorrect initial conditions
66  Values values;
67  values.insert(poseKey1, pose1.retract((Vector(6) << +0.01, -0.02, +0.03, -0.10, +0.20, -0.30).finished()));
68  values.insert(poseKey2, pose2.retract((Vector(6) << +0.01, +0.02, -0.03, -0.10, +0.20, +0.30).finished()));
69  values.insert(landmarkKey, Vector3(expected + Vector3(+0.02, -0.04, +0.05)));
70 
71  // Optimize the graph to recover the actual landmark position
74  Vector3 actual = result.at<Vector3>(landmarkKey);
75 
76 
77 
78  // Test that the correct landmark parameters have been recovered
79  EXPECT(assert_equal((Vector)expected, actual, 1e-9));
80 }
81 
82 
83 /* ************************************************************************* */
84 int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
85 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
camera1
PinholeCamera< Cal3_S2 > camera1(pose1, *sharedCal)
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
gtsam::Pose3::transformTo
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in world coordinates and transforms it to Pose coordinates
Definition: Pose3.cpp:371
simple_graph::factor2
auto factor2
Definition: testJacobianFactor.cpp:203
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
optimize
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:64
Cal3_S2.h
The most common 5DOF 3D->2D calibration.
TestHarness.h
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
Point3.h
3D Point
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::NonlinearEquality
Definition: NonlinearEquality.h:43
gtsam::PinholeBaseK::project
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:170
Point2.h
2D Point
InvDepthFactorVariant3.h
Inverse Depth Factor based on Civera09tro, Montiel06rss. Landmarks are parameterized as (theta,...
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
gtsam::Pose3
Definition: Pose3.h:37
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
landmark
static Point3 landmark(0, 0, 5)
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
gtsam::InvDepthFactorVariant3a
Definition: InvDepthFactorVariant3.h:25
Symbol.h
gtsam::HybridValues::insert
void insert(Key j, const Vector &value)
Definition: HybridValues.cpp:85
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::Cal3_S2::shared_ptr
std::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
NonlinearEquality.h
TestResult
Definition: TestResult.h:26
atan2
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:110
simple_graph::factor3
auto factor3
Definition: testJacobianFactor.cpp:210
gtsam
traits
Definition: SFMdata.h:40
poseKey2
static Key poseKey2(X(2))
pose1
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
K
#define K
Definition: igam.h:8
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
gtsam::InvDepthFactorVariant3b
Definition: InvDepthFactorVariant3.h:155
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
TEST
TEST(InvDepthFactorVariant3, optimize)
Definition: testInvDepthFactorVariant3.cpp:24
gtsam::LieGroup::retract
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:131
poseKey1
static Key poseKey1(X(1))
main
int main()
Definition: testInvDepthFactorVariant3.cpp:84
M_PI
#define M_PI
Definition: mconf.h:117
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
camera2
static const Camera2 camera2(pose1, K2)
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
simple_graph::factor1
auto factor1
Definition: testJacobianFactor.cpp:196
Pose3.h
3D Pose


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:47