testAdaptAutoDiff.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
24 #include <gtsam/geometry/Pose3.h>
25 #include <gtsam/geometry/Cal3_S2.h>
28 #include <gtsam/base/Testable.h>
29 
31 
32 #include <boost/assign/list_of.hpp>
33 using boost::assign::list_of;
34 using boost::assign::map_list_of;
35 
36 namespace gtsam {
37 
38 // Special version of Cal3Bundler so that default constructor = 0,0,0
39 struct Cal3Bundler0 : public Cal3Bundler {
40  Cal3Bundler0(double f = 0, double k1 = 0, double k2 = 0, double u0 = 0,
41  double v0 = 0)
42  : Cal3Bundler(f, k1, k2, u0, v0) {}
43  Cal3Bundler0 retract(const Vector& d) const {
44  return Cal3Bundler0(fx() + d(0), k1() + d(1), k2() + d(2), px(), py());
45  }
47  return T2.vector() - vector();
48  }
49 };
50 
51 template <>
52 struct traits<Cal3Bundler0> : public internal::Manifold<Cal3Bundler0> {};
53 
54 // With that, camera below behaves like Snavely's 9-dim vector
56 }
57 
58 using namespace std;
59 using namespace gtsam;
60 
61 /* ************************************************************************* */
62 // Check that ceres rotation convention is the same
63 TEST(AdaptAutoDiff, Rotation) {
64  Vector3 axisAngle(0.1, 0.2, 0.3);
65  Matrix3 expected = Rot3::Rodrigues(axisAngle).matrix();
66  Matrix3 actual;
67  ceres::AngleAxisToRotationMatrix(axisAngle.data(), actual.data());
68  EXPECT(assert_equal(expected, actual));
69 }
70 
71 /* ************************************************************************* */
72 // Some Ceres Snippets copied for testing
73 // Copyright 2010, 2011, 2012 Google Inc. All rights reserved.
74 template <typename T>
75 inline T& RowMajorAccess(T* base, int rows, int cols, int i, int j) {
76  return base[cols * i + j];
77 }
78 
79 inline double RandDouble() {
80  double r = static_cast<double>(rand());
81  return r / RAND_MAX;
82 }
83 
84 // A structure for projecting a 3x4 camera matrix and a
85 // homogeneous 3D point, to a 2D inhomogeneous point.
86 struct Projective {
87  // Function that takes P and X as separate vectors:
88  // P, X -> x
89  template <typename A>
90  bool operator()(A const P[12], A const X[4], A x[2]) const {
91  A PX[3];
92  for (int i = 0; i < 3; ++i) {
93  PX[i] = RowMajorAccess(P, 3, 4, i, 0) * X[0] +
94  RowMajorAccess(P, 3, 4, i, 1) * X[1] +
95  RowMajorAccess(P, 3, 4, i, 2) * X[2] +
96  RowMajorAccess(P, 3, 4, i, 3) * X[3];
97  }
98  if (PX[2] != 0.0) {
99  x[0] = PX[0] / PX[2];
100  x[1] = PX[1] / PX[2];
101  return true;
102  }
103  return false;
104  }
105 
106  // Adapt to eigen types
107  Vector2 operator()(const MatrixRowMajor& P, const Vector4& X) const {
108  Vector2 x;
109  if (operator()(P.data(), X.data(), x.data()))
110  return x;
111  else
112  throw std::runtime_error("Projective fail");
113  }
114 };
115 
116 /* ************************************************************************* */
117 // Test Ceres AutoDiff
118 TEST(AdaptAutoDiff, AutoDiff) {
120 
121  // Instantiate function
122  Projective projective;
123 
124  // Make arguments
125  typedef Eigen::Matrix<double, 3, 4, Eigen::RowMajor> RowMajorMatrix34;
126  RowMajorMatrix34 P;
127  P << 1, 0, 0, 0, 0, 1, 0, 5, 0, 0, 1, 0;
128  Vector4 X(10, 0, 5, 1);
129 
130  // Apply the mapping, to get image point b_x.
131  Vector expected = Vector2(2, 1);
132  Vector2 actual = projective(P, X);
133  EXPECT(assert_equal(expected, actual, 1e-9));
134 
135  // Get expected derivatives
136  Matrix E1 = numericalDerivative21<Vector2, RowMajorMatrix34, Vector4>(
137  Projective(), P, X);
138  Matrix E2 = numericalDerivative22<Vector2, RowMajorMatrix34, Vector4>(
139  Projective(), P, X);
140 
141  // Get derivatives with AutoDiff
142  Vector2 actual2;
143  MatrixRowMajor H1(2, 12), H2(2, 4);
144  double* parameters[] = {P.data(), X.data()};
145  double* jacobians[] = {H1.data(), H2.data()};
146  CHECK((AutoDiff<Projective, double, 12, 4>::Differentiate(
147  projective, parameters, 2, actual2.data(), jacobians)));
148  EXPECT(assert_equal(E1, H1, 1e-8));
149  EXPECT(assert_equal(E2, H2, 1e-8));
150 }
151 
152 /* ************************************************************************* */
153 // Test Ceres AutoDiff on Snavely, defined in ceres_example.h
154 // Adapt to GTSAM types
155 Vector2 adapted(const Vector9& P, const Vector3& X) {
156  SnavelyProjection snavely;
157  Vector2 x;
158  if (snavely(P.data(), X.data(), x.data()))
159  return x;
160  else
161  throw std::runtime_error("Snavely fail");
162 }
163 
164 /* ************************************************************************* */
165 namespace example {
166 Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)),
167  Cal3Bundler0(1, 0, 0));
168 Point3 point(10, 0, -5); // negative Z-axis convention of Snavely!
169 Vector9 P = Camera().localCoordinates(camera);
171 #ifdef GTSAM_POSE3_EXPMAP
172 Vector2 expectedMeasurement(1.3124675, 1.2057287);
173 #else
174 Vector2 expectedMeasurement(1.2431567, 1.2525694);
175 #endif
176 Matrix E1 = numericalDerivative21<Vector2, Vector9, Vector3>(adapted, P, X);
177 Matrix E2 = numericalDerivative22<Vector2, Vector9, Vector3>(adapted, P, X);
178 }
179 
180 /* ************************************************************************* */
181 // Check that Local worked as expected
183  using namespace example;
184 #ifdef GTSAM_POSE3_EXPMAP
185  Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0.7583528428, 4.9582357859, -0.224941471539, 1, 0, 0).finished();
186 #else
187  Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0, 5, 0, 1, 0, 0).finished();
188 #endif
189  EXPECT(equal_with_abs_tol(expectedP, P));
190  Vector3 expectedX(10, 0, -5); // negative Z-axis convention of Snavely!
191  EXPECT(equal_with_abs_tol(expectedX, X));
192 }
193 
194 /* ************************************************************************* */
195 // Test Ceres AutoDiff
196 TEST(AdaptAutoDiff, AutoDiff2) {
197  using namespace example;
199 
200  // Apply the mapping, to get image point b_x.
201  Vector2 actual = adapted(P, X);
203 
204  // Instantiate function
205  SnavelyProjection snavely;
206 
207  // Get derivatives with AutoDiff
208  Vector2 actual2;
209  MatrixRowMajor H1(2, 9), H2(2, 3);
210  double* parameters[] = {P.data(), X.data()};
211  double* jacobians[] = {H1.data(), H2.data()};
212  CHECK((AutoDiff<SnavelyProjection, double, 9, 3>::Differentiate(
213  snavely, parameters, 2, actual2.data(), jacobians)));
214  EXPECT(assert_equal(E1, H1, 1e-8));
215  EXPECT(assert_equal(E2, H2, 1e-8));
216 }
217 
218 /* ************************************************************************* */
219 // Test AutoDiff wrapper Snavely
221  using namespace example;
222 
224  Adaptor snavely;
225 
226  // Apply the mapping, to get image point b_x.
227  Vector2 actual = snavely(P, X);
229 
230  // Get derivatives with AutoDiff, not gives RowMajor results!
231  Matrix29 H1;
232  Matrix23 H2;
233  Vector2 actual2 = snavely(P, X, H1, H2);
234  EXPECT(assert_equal(expectedMeasurement, actual2, 1e-6));
235  EXPECT(assert_equal(E1, H1, 1e-8));
236  EXPECT(assert_equal(E2, H2, 1e-8));
237 }
238 
239 /* ************************************************************************* */
240 // Test AutoDiff wrapper in an expression
241 TEST(AdaptAutoDiff, SnavelyExpression) {
243 
246 
247  Expression<Vector2> expression(Adaptor(), P, X);
248 
249  std::size_t RecordSize =
251 
253  internal::upAligned(RecordSize) + P.traceSize() + X.traceSize(),
254  expression.traceSize());
255 
256  set<Key> expected = list_of(1)(2);
257 
258  EXPECT(expected == expression.keys());
259 }
260 
261 /* ************************************************************************* */
262 int main() {
263  TestResult tr;
264  return TestRegistry::runAllTests(tr);
265 }
266 /* ************************************************************************* */
#define CHECK(condition)
Definition: Test.h:109
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
Vector3 vector() const
Definition: Cal3Bundler.cpp:42
Adaptor for Ceres style auto-differentiated functions.
Concept check for values that can be used in unit tests.
double RandDouble()
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
double k1() const
distorsion parameter k1
Definition: Cal3Bundler.h:84
Matrix expected
Definition: testMatrix.cpp:974
PinholeCamera< Cal3Bundler0 > Camera
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
Vector2 adapted(const Vector9 &P, const Vector3 &X)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Vector2 operator()(const MatrixRowMajor &P, const Vector4 &X) const
T & RowMajorAccess(T *base, int rows, int cols, int i, int j)
Definition: Half.h:150
double k2() const
distorsion parameter k2
Definition: Cal3Bundler.h:87
Some functions to compute numerical derivatives.
Matrix3 matrix() const
Definition: Rot3M.cpp:219
Cal3Bundler0 retract(const Vector &d) const
T upAligned(T value, unsigned requiredAlignment=TraceAlignment)
Cal3Bundler0(double f=0, double k1=0, double k2=0, double u0=0, double v0=0)
Expressions for Block Automatic Differentiation.
Point3 point(10, 0,-5)
Base class for all pinhole cameras.
int main()
bool operator()(A const P[12], A const X[4], A x[2]) const
static Rot3 Rodrigues(const Vector3 &w)
Definition: Rot3.h:243
Eigen::VectorXd Vector
Definition: Vector.h:38
#define EXPECT(condition)
Definition: Test.h:151
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector3 localCoordinates(const Cal3Bundler0 &T2) const
static const double u0
std::set< Key > keys() const
Return keys that play in this expression.
static ConjugateGradientParameters parameters
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
double px() const
image center in x
Definition: Cal3Bundler.h:90
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Eigen::Vector2d Vector2
Definition: Vector.h:42
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
static const double v0
TEST(LPInitSolver, InfiniteLoopSingleVar)
size_t traceSize() const
Return size needed for memory buffer in traceExecution.
Vector2 expectedMeasurement(1.2431567, 1.2525694)
double fx() const
focal length x
Definition: Cal3.h:139
Annotation indicating that a class derives from another given type.
Definition: attr.h:42
Vector3 Point3
Definition: Point3.h:35
Definition: camera.h:36
The matrix class, also used for vectors and row-vectors.
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
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
double py() const
image center in y
Definition: Cal3Bundler.h:93
3D Pose
Calibration used by Bundler.
std::ptrdiff_t j
The most common 5DOF 3D->2D calibration.
void AngleAxisToRotationMatrix(const T *angle_axis, T *R)
Definition: rotation.h:390


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:04