testInvDepthFactorVariant1.cpp
Go to the documentation of this file.
1 /*
2  * testInvDepthFactorVariant1.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 /* ************************************************************************* */
25 
26  // Create two poses looking in the x-direction
27  Pose3 pose1(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.0));
28  Pose3 pose2(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), 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  double x = pose1.translation().x();
42  double y = pose1.translation().y();
43  double z = pose1.translation().z();
44  Point3 ray = landmark - pose1.translation();
45  double theta = atan2(ray.y(), ray.x());
46  double phi = atan2(ray.z(), sqrt(ray.x()*ray.x()+ray.y()*ray.y()));
47  double rho = 1./ray.norm();
48  Vector6 expected((Vector(6) << x, y, z, theta, phi, rho).finished());
49 
50 
51 
52  // Create a factor graph with two inverse depth factors and two pose priors
53  Key poseKey1(1);
54  Key poseKey2(2);
55  Key landmarkKey(100);
56  SharedNoiseModel sigma(noiseModel::Unit::Create(2));
60  NonlinearFactor::shared_ptr factor4(new InvDepthFactorVariant1(poseKey2, landmarkKey, pixel2, K, sigma));
65  graph.push_back(factor4);
66 
67  // Create a values with slightly incorrect initial conditions
68  Values values;
69  values.insert(poseKey1, pose1.retract((Vector(6) << +0.01, -0.02, +0.03, -0.10, +0.20, -0.30).finished()));
70  values.insert(poseKey2, pose2.retract((Vector(6) << +0.01, +0.02, -0.03, -0.10, +0.20, +0.30).finished()));
71  values.insert(landmarkKey, Vector6(expected + (Vector(6) << -0.20, +0.20, -0.35, +0.02, -0.04, +0.05).finished()));
72 
73  // Optimize the graph to recover the actual landmark position
76 
77 // Vector6 actual = result.at<Vector6>(landmarkKey);
78 // values.at<Pose3>(poseKey1).print("Pose1 Before:\n");
79 // result.at<Pose3>(poseKey1).print("Pose1 After:\n");
80 // pose1.print("Pose1 Truth:\n");
81 // cout << endl << endl;
82 // values.at<Pose3>(poseKey2).print("Pose2 Before:\n");
83 // result.at<Pose3>(poseKey2).print("Pose2 After:\n");
84 // pose2.print("Pose2 Truth:\n");
85 // cout << endl << endl;
86 // values.at<Vector6>(landmarkKey).print("Landmark Before:\n");
87 // result.at<Vector6>(landmarkKey).print("Landmark After:\n");
88 // expected.print("Landmark Truth:\n");
89 // cout << endl << endl;
90 
91  // Calculate world coordinates of landmark versions
92  Point3 world_landmarkBefore(0,0,0);
93  {
94  Vector6 landmarkBefore = values.at<Vector6>(landmarkKey);
95  double x = landmarkBefore(0), y = landmarkBefore(1), z = landmarkBefore(2);
96  double theta = landmarkBefore(3), phi = landmarkBefore(4), rho = landmarkBefore(5);
97  world_landmarkBefore = Point3(x, y, z) + Point3(cos(theta)*cos(phi)/rho, sin(theta)*cos(phi)/rho, sin(phi)/rho);
98  }
99  Point3 world_landmarkAfter(0,0,0);
100  {
101  Vector6 landmarkAfter = result.at<Vector6>(landmarkKey);
102  double x = landmarkAfter(0), y = landmarkAfter(1), z = landmarkAfter(2);
103  double theta = landmarkAfter(3), phi = landmarkAfter(4), rho = landmarkAfter(5);
104  world_landmarkAfter = Point3(x, y, z) + Point3(cos(theta)*cos(phi)/rho, sin(theta)*cos(phi)/rho, sin(phi)/rho);
105  }
106 
107 // world_landmarkBefore.print("World Landmark Before:\n");
108 // world_landmarkAfter.print("World Landmark After:\n");
109 // landmark.print("World Landmark Truth:\n");
110 // cout << endl << endl;
111 
112 
113 
114  // Test that the correct landmark parameters have been recovered
115  // However, since this is an over-parameterization, there can be
116  // many 6D landmark values that equate to the same 3D world position
117  // Instead, directly test the recovered 3D landmark position
118  EXPECT(assert_equal(landmark, world_landmarkAfter, 1e-9));
119 
120  // Frank asks: why commented out?
121  //Vector6 actual = result.at<Vector6>(landmarkKey);
122  //EXPECT(assert_equal(expected, actual, 1e-9));
123 }
124 
125 
126 /* ************************************************************************* */
127 int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
128 /* ************************************************************************* */
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
TEST
TEST(InvDepthFactorVariant1, optimize)
Definition: testInvDepthFactorVariant1.cpp:24
simple_graph::factor2
auto factor2
Definition: testJacobianFactor.cpp:203
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
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.
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
Point3.h
3D Point
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
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:169
Point2.h
2D Point
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
gtsam::Pose3::translation
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:308
landmark
static Point3 landmark(0, 0, 5)
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
Symbol.h
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
gtsam::Cal3_S2::shared_ptr
std::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
NonlinearEquality.h
InvDepthFactorVariant1.h
Inverse Depth Factor based on Civera09tro, Montiel06rss. Landmarks are parameterized as (x,...
gtsam::InvDepthFactorVariant1
Definition: InvDepthFactorVariant1.h:25
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
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: chartTesting.h:28
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.
leaf::values
leaf::MyValues values
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::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp: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
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))
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
main
int main()
Definition: testInvDepthFactorVariant1.cpp:127
Pose3.h
3D Pose


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:06:04