testChebyshev2.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 
21 #include <gtsam/base/Testable.h>
22 #include <gtsam/basis/Chebyshev2.h>
23 #include <gtsam/basis/FitBasis.h>
24 #include <gtsam/geometry/Pose2.h>
25 #include <gtsam/geometry/Pose3.h>
27 
28 #include <cstddef>
29 #include <functional>
30 
31 using namespace std;
32 using namespace gtsam;
33 
34 namespace {
35 noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1);
36 
37 const size_t N = 32;
38 } // namespace
39 
40 //******************************************************************************
41 TEST(Chebyshev2, Point) {
42  static const int N = 5;
43  auto points = Chebyshev2::Points(N);
44  Vector expected(N);
45  expected << -1., -sqrt(2.) / 2., 0., sqrt(2.) / 2., 1.;
46  static const double tol = 1e-15; // changing this reveals errors
47  EXPECT_DOUBLES_EQUAL(expected(0), points(0), tol);
48  EXPECT_DOUBLES_EQUAL(expected(1), points(1), tol);
49  EXPECT_DOUBLES_EQUAL(expected(2), points(2), tol);
50  EXPECT_DOUBLES_EQUAL(expected(3), points(3), tol);
51  EXPECT_DOUBLES_EQUAL(expected(4), points(4), tol);
52 
53  // Check symmetry
54  EXPECT_DOUBLES_EQUAL(Chebyshev2::Point(N, 0), -Chebyshev2::Point(N, 4), tol);
55  EXPECT_DOUBLES_EQUAL(Chebyshev2::Point(N, 1), -Chebyshev2::Point(N, 3), tol);
56 }
57 
58 //******************************************************************************
59 TEST(Chebyshev2, PointInInterval) {
60  static const int N = 5;
61  auto points = Chebyshev2::Points(N, 0, 20);
62  Vector expected(N);
63  expected << 0., 1. - sqrt(2.) / 2., 1., 1. + sqrt(2.) / 2., 2.;
64  expected *= 10.0;
65  static const double tol = 1e-15; // changing this reveals errors
66  EXPECT_DOUBLES_EQUAL(expected(0), points(0), tol);
67  EXPECT_DOUBLES_EQUAL(expected(1), points(1), tol);
68  EXPECT_DOUBLES_EQUAL(expected(2), points(2), tol);
69  EXPECT_DOUBLES_EQUAL(expected(3), points(3), tol);
70  EXPECT_DOUBLES_EQUAL(expected(4), points(4), tol);
71 
72  // all at once
73  Vector actual = Chebyshev2::Points(N, 0, 20);
74  CHECK(assert_equal(expected, actual));
75 }
76 
77 //******************************************************************************
78 // InterpolatingPolynomial[{{-1, 4}, {0, 2}, {1, 6}}, 0.5]
79 TEST(Chebyshev2, Interpolate2) {
80  size_t N = 3;
81  Chebyshev2::EvaluationFunctor fx(N, 0.5);
82  Vector f(N);
83  f << 4, 2, 6;
84  EXPECT_DOUBLES_EQUAL(3.25, fx(f), 1e-9);
85 }
86 
87 //******************************************************************************
88 // InterpolatingPolynomial[{{0, 4}, {1, 2}, {2, 6}}, 1.5]
89 TEST(Chebyshev2, Interpolate2_Interval) {
90  Chebyshev2::EvaluationFunctor fx(3, 1.5, 0, 2);
91  Vector3 f(4, 2, 6);
92  EXPECT_DOUBLES_EQUAL(3.25, fx(f), 1e-9);
93 }
94 
95 //******************************************************************************
96 // InterpolatingPolynomial[{{-1, 4}, {-Sqrt[2]/2, 2}, {0, 6}, {Sqrt[2]/2,3}, {1,
97 // 3}}, 0.5]
98 TEST(Chebyshev2, Interpolate5) {
99  Chebyshev2::EvaluationFunctor fx(5, 0.5);
100  Vector f(5);
101  f << 4, 2, 6, 3, 3;
102  EXPECT_DOUBLES_EQUAL(4.34283, fx(f), 1e-5);
103 }
104 
105 //******************************************************************************
106 // Interpolating vectors
107 TEST(Chebyshev2, InterpolateVector) {
108  double t = 30, a = 0, b = 100;
109  const size_t N = 3;
110  // Create 2x3 matrix with Vectors at Chebyshev points
111  Matrix X = Matrix::Zero(2, N);
112  X.row(0) = Chebyshev2::Points(N, a, b); // slope 1 ramp
113 
114  // Check value
115  Vector expected(2);
116  expected << t, 0;
117  Eigen::Matrix<double, /*2x2N*/ -1, -1> actualH(2, 2 * N);
118 
119  Chebyshev2::VectorEvaluationFunctor fx(2, N, t, a, b);
120  EXPECT(assert_equal(expected, fx(X, actualH), 1e-9));
121 
122  // Check derivative
123  std::function<Vector2(Matrix)> f =
124  std::bind(&Chebyshev2::VectorEvaluationFunctor::operator(), fx,
125  std::placeholders::_1, nullptr);
126  Matrix numericalH =
127  numericalDerivative11<Vector2, Matrix, 2 * N>(f, X);
128  EXPECT(assert_equal(numericalH, actualH, 1e-9));
129 }
130 
131 //******************************************************************************
132 // Interpolating poses using the exponential map
133 TEST(Chebyshev2, InterpolatePose2) {
134  double t = 30, a = 0, b = 100;
135 
136  Matrix X(3, N);
137  X.row(0) = Chebyshev2::Points(N, a, b); // slope 1 ramp
138  X.row(1) = Vector::Zero(N);
139  X.row(2) = 0.1 * Vector::Ones(N);
140 
141  Vector xi(3);
142  xi << t, 0, 0.1;
143  Eigen::Matrix<double, /*3x3N*/ -1, -1> actualH(3, 3 * N);
144 
145  Chebyshev2::ManifoldEvaluationFunctor<Pose2> fx(N, t, a, b);
146  // We use xi as canonical coordinates via exponential map
147  Pose2 expected = Pose2::ChartAtOrigin::Retract(xi);
148  EXPECT(assert_equal(expected, fx(X, actualH)));
149 
150  // Check derivative
151  std::function<Pose2(Matrix)> f =
152  std::bind(&Chebyshev2::ManifoldEvaluationFunctor<Pose2>::operator(), fx,
153  std::placeholders::_1, nullptr);
154  Matrix numericalH =
155  numericalDerivative11<Pose2, Matrix, 3 * N>(f, X);
156  EXPECT(assert_equal(numericalH, actualH, 1e-9));
157 }
158 
159 #ifdef GTSAM_POSE3_EXPMAP
160 //******************************************************************************
161 // Interpolating poses using the exponential map
162 TEST(Chebyshev2, InterpolatePose3) {
163  double a = 10, b = 100;
164  double t = Chebyshev2::Points(N, a, b)(11);
165 
166  Rot3 R = Rot3::Ypr(-2.21366492e-05, -9.35353636e-03, -5.90463598e-04);
167  Pose3 pose(R, Point3(1, 2, 3));
168 
169  Vector6 xi = Pose3::ChartAtOrigin::Local(pose);
170  Eigen::Matrix<double, /*6x6N*/ -1, -1> actualH(6, 6 * N);
171 
172  Matrix X = Matrix::Zero(6, N);
173  X.col(11) = xi;
174 
175  Chebyshev2::ManifoldEvaluationFunctor<Pose3> fx(N, t, a, b);
176  // We use xi as canonical coordinates via exponential map
177  Pose3 expected = Pose3::ChartAtOrigin::Retract(xi);
178  EXPECT(assert_equal(expected, fx(X, actualH)));
179 
180  // Check derivative
181  std::function<Pose3(Matrix)> f =
182  std::bind(&Chebyshev2::ManifoldEvaluationFunctor<Pose3>::operator(), fx,
183  std::placeholders::_1, nullptr);
184  Matrix numericalH =
185  numericalDerivative11<Pose3, Matrix, 6 * N>(f, X);
186  EXPECT(assert_equal(numericalH, actualH, 1e-8));
187 }
188 #endif
189 
190 //******************************************************************************
191 TEST(Chebyshev2, Decomposition) {
192  // Create example sequence
194  for (size_t i = 0; i < 16; i++) {
195  double x = (1.0 / 16) * i - 0.99, y = x;
196  sequence[x] = y;
197  }
198 
199  // Do Chebyshev Decomposition
200  FitBasis<Chebyshev2> actual(sequence, model, 3);
201 
202  // Check
203  Vector expected(3);
204  expected << -1, 0, 1;
205  EXPECT(assert_equal(expected, actual.parameters(), 1e-4));
206 }
207 
208 //******************************************************************************
209 TEST(Chebyshev2, DifferentiationMatrix3) {
210  // Trefethen00book, p.55
211  const size_t N = 3;
212  Matrix expected(N, N);
213  // Differentiation matrix computed from chebfun
214  expected << 1.5000, -2.0000, 0.5000, //
215  0.5000, -0.0000, -0.5000, //
216  -0.5000, 2.0000, -1.5000;
217  // multiply by -1 since the chebyshev points have a phase shift wrt Trefethen
218  // This was verified with chebfun
219  expected = -expected;
220 
221  Matrix actual = Chebyshev2::DifferentiationMatrix(N);
222  EXPECT(assert_equal(expected, actual, 1e-4));
223 }
224 
225 //******************************************************************************
226 TEST(Chebyshev2, DerivativeMatrix6) {
227  // Trefethen00book, p.55
228  const size_t N = 6;
229  Matrix expected(N, N);
230  expected << 8.5000, -10.4721, 2.8944, -1.5279, 1.1056, -0.5000, //
231  2.6180, -1.1708, -2.0000, 0.8944, -0.6180, 0.2764, //
232  -0.7236, 2.0000, -0.1708, -1.6180, 0.8944, -0.3820, //
233  0.3820, -0.8944, 1.6180, 0.1708, -2.0000, 0.7236, //
234  -0.2764, 0.6180, -0.8944, 2.0000, 1.1708, -2.6180, //
235  0.5000, -1.1056, 1.5279, -2.8944, 10.4721, -8.5000;
236  // multiply by -1 since the chebyshev points have a phase shift wrt Trefethen
237  // This was verified with chebfun
238  expected = -expected;
239 
240  Matrix actual = Chebyshev2::DifferentiationMatrix(N);
241  EXPECT(assert_equal((Matrix)expected, actual, 1e-4));
242 }
243 
244 // test function for CalculateWeights and DerivativeWeights
245 double f(double x) {
246  // return 3*(x**3) - 2*(x**2) + 5*x - 11
247  return 3.0 * pow(x, 3) - 2.0 * pow(x, 2) + 5.0 * x - 11;
248 }
249 
250 // its derivative
251 double fprime(double x) {
252  // return 9*(x**2) - 4*(x) + 5
253  return 9.0 * pow(x, 2) - 4.0 * x + 5.0;
254 }
255 
256 //******************************************************************************
257 TEST(Chebyshev2, CalculateWeights) {
258  Eigen::Matrix<double, -1, 1> fvals(N);
259  for (size_t i = 0; i < N; i++) {
260  fvals(i) = f(Chebyshev2::Point(N, i));
261  }
262  double x1 = 0.7, x2 = -0.376;
263  Weights weights1 = Chebyshev2::CalculateWeights(N, x1);
264  Weights weights2 = Chebyshev2::CalculateWeights(N, x2);
265  EXPECT_DOUBLES_EQUAL(f(x1), weights1 * fvals, 1e-8);
266  EXPECT_DOUBLES_EQUAL(f(x2), weights2 * fvals, 1e-8);
267 }
268 
269 TEST(Chebyshev2, CalculateWeights2) {
270  double a = 0, b = 10, x1 = 7, x2 = 4.12;
271 
272  Eigen::Matrix<double, -1, 1> fvals(N);
273  for (size_t i = 0; i < N; i++) {
274  fvals(i) = f(Chebyshev2::Point(N, i, a, b));
275  }
276 
277  Weights weights1 = Chebyshev2::CalculateWeights(N, x1, a, b);
278  EXPECT_DOUBLES_EQUAL(f(x1), weights1 * fvals, 1e-8);
279 
280  Weights weights2 = Chebyshev2::CalculateWeights(N, x2, a, b);
281  double expected2 = f(x2); // 185.454784
282  double actual2 = weights2 * fvals;
283  EXPECT_DOUBLES_EQUAL(expected2, actual2, 1e-8);
284 }
285 
286 TEST(Chebyshev2, DerivativeWeights) {
287  Eigen::Matrix<double, -1, 1> fvals(N);
288  for (size_t i = 0; i < N; i++) {
289  fvals(i) = f(Chebyshev2::Point(N, i));
290  }
291  double x1 = 0.7, x2 = -0.376, x3 = 0.0;
292  Weights dWeights1 = Chebyshev2::DerivativeWeights(N, x1);
293  EXPECT_DOUBLES_EQUAL(fprime(x1), dWeights1 * fvals, 1e-9);
294 
295  Weights dWeights2 = Chebyshev2::DerivativeWeights(N, x2);
296  EXPECT_DOUBLES_EQUAL(fprime(x2), dWeights2 * fvals, 1e-9);
297 
298  Weights dWeights3 = Chebyshev2::DerivativeWeights(N, x3);
299  EXPECT_DOUBLES_EQUAL(fprime(x3), dWeights3 * fvals, 1e-9);
300 
301  // test if derivative calculation and cheb point is correct
302  double x4 = Chebyshev2::Point(N, 3);
303  Weights dWeights4 = Chebyshev2::DerivativeWeights(N, x4);
304  EXPECT_DOUBLES_EQUAL(fprime(x4), dWeights4 * fvals, 1e-9);
305 }
306 
307 TEST(Chebyshev2, DerivativeWeights2) {
308  double x1 = 5, x2 = 4.12, a = 0, b = 10;
309 
310  Eigen::Matrix<double, -1, 1> fvals(N);
311  for (size_t i = 0; i < N; i++) {
312  fvals(i) = f(Chebyshev2::Point(N, i, a, b));
313  }
314 
315  Weights dWeights1 = Chebyshev2::DerivativeWeights(N, x1, a, b);
316  EXPECT_DOUBLES_EQUAL(fprime(x1), dWeights1 * fvals, 1e-8);
317 
318  Weights dWeights2 = Chebyshev2::DerivativeWeights(N, x2, a, b);
319  EXPECT_DOUBLES_EQUAL(fprime(x2), dWeights2 * fvals, 1e-8);
320 
321  // test if derivative calculation and Chebyshev point is correct
322  double x3 = Chebyshev2::Point(N, 3, a, b);
323  Weights dWeights3 = Chebyshev2::DerivativeWeights(N, x3, a, b);
324  EXPECT_DOUBLES_EQUAL(fprime(x3), dWeights3 * fvals, 1e-8);
325 }
326 
327 //******************************************************************************
328 // Check two different ways to calculate the derivative weights
329 TEST(Chebyshev2, DerivativeWeightsDifferentiationMatrix) {
330  const size_t N6 = 6;
331  double x1 = 0.311;
332  Matrix D6 = Chebyshev2::DifferentiationMatrix(N6);
333  Weights expected = Chebyshev2::CalculateWeights(N6, x1) * D6;
334  Weights actual = Chebyshev2::DerivativeWeights(N6, x1);
335  EXPECT(assert_equal(expected, actual, 1e-12));
336 
337  double a = -3, b = 8, x2 = 5.05;
338  Matrix D6_2 = Chebyshev2::DifferentiationMatrix(N6, a, b);
339  Weights expected1 = Chebyshev2::CalculateWeights(N6, x2, a, b) * D6_2;
340  Weights actual1 = Chebyshev2::DerivativeWeights(N6, x2, a, b);
341  EXPECT(assert_equal(expected1, actual1, 1e-12));
342 }
343 
344 //******************************************************************************
345 // Check two different ways to calculate the derivative weights
346 TEST(Chebyshev2, DerivativeWeights6) {
347  const size_t N6 = 6;
348  Matrix D6 = Chebyshev2::DifferentiationMatrix(N6);
349  Chebyshev2::Parameters x = Chebyshev2::Points(N6); // ramp with slope 1
350  EXPECT(assert_equal(Vector::Ones(N6), Vector(D6 * x)));
351 }
352 
353 //******************************************************************************
354 // Check two different ways to calculate the derivative weights
355 TEST(Chebyshev2, DerivativeWeights7) {
356  const size_t N7 = 7;
357  Matrix D7 = Chebyshev2::DifferentiationMatrix(N7);
358  Chebyshev2::Parameters x = Chebyshev2::Points(N7); // ramp with slope 1
359  EXPECT(assert_equal(Vector::Ones(N7), Vector(D7 * x)));
360 }
361 
362 //******************************************************************************
363 // Check derivative in two different ways: numerical and using D on f
364 Vector6 f3_at_6points = (Vector6() << 4, 2, 6, 2, 4, 3).finished();
365 double proxy3(double x) {
366  return Chebyshev2::EvaluationFunctor(6, x)(f3_at_6points);
367 }
368 
369 TEST(Chebyshev2, Derivative6) {
370  // Check Derivative evaluation at point x=0.2
371 
372  // calculate expected values by numerical derivative of synthesis
373  const double x = 0.2;
374  Matrix numeric_dTdx = numericalDerivative11<double, double>(proxy3, x);
375 
376  // Calculate derivatives at Chebyshev points using D3, interpolate
377  Matrix D6 = Chebyshev2::DifferentiationMatrix(6);
378  Vector derivative_at_points = D6 * f3_at_6points;
379  Chebyshev2::EvaluationFunctor fx(6, x);
380  EXPECT_DOUBLES_EQUAL(numeric_dTdx(0, 0), fx(derivative_at_points), 1e-8);
381 
382  // Do directly
383  Chebyshev2::DerivativeFunctor dfdx(6, x);
384  EXPECT_DOUBLES_EQUAL(numeric_dTdx(0, 0), dfdx(f3_at_6points), 1e-8);
385 }
386 
387 //******************************************************************************
388 // Assert that derivative also works in non-standard interval [0,3]
389 double proxy4(double x) {
390  return Chebyshev2::EvaluationFunctor(6, x, 0, 3)(f3_at_6points);
391 }
392 
393 TEST(Chebyshev2, Derivative6_03) {
394  // Check Derivative evaluation at point x=0.2, in interval [0,3]
395 
396  // calculate expected values by numerical derivative of synthesis
397  const double x = 0.2;
398  Matrix numeric_dTdx = numericalDerivative11<double, double>(proxy4, x);
399 
400  // Calculate derivatives at Chebyshev points using D3, interpolate
401  Matrix D6 = Chebyshev2::DifferentiationMatrix(6, 0, 3);
402  Vector derivative_at_points = D6 * f3_at_6points;
403  Chebyshev2::EvaluationFunctor fx(6, x, 0, 3);
404  EXPECT_DOUBLES_EQUAL(numeric_dTdx(0, 0), fx(derivative_at_points), 1e-8);
405 
406  // Do directly
407  Chebyshev2::DerivativeFunctor dfdx(6, x, 0, 3);
408  EXPECT_DOUBLES_EQUAL(numeric_dTdx(0, 0), dfdx(f3_at_6points), 1e-8);
409 }
410 
411 //******************************************************************************
412 // Test VectorDerivativeFunctor
413 TEST(Chebyshev2, VectorDerivativeFunctor) {
414  const size_t N = 3, M = 2;
415  const double x = 0.2;
416  using VecD = Chebyshev2::VectorDerivativeFunctor;
417  VecD fx(M, N, x, 0, 3);
418  Matrix X = Matrix::Zero(M, N);
419  Matrix actualH(M, M * N);
420  EXPECT(assert_equal(Vector::Zero(M), (Vector)fx(X, actualH), 1e-8));
421 
422  // Test Jacobian
423  Matrix expectedH = numericalDerivative11<Vector2, Matrix, M * N>(
424  std::bind(&VecD::operator(), fx, std::placeholders::_1, nullptr), X);
425  EXPECT(assert_equal(expectedH, actualH, 1e-7));
426 }
427 
428 //******************************************************************************
429 // Test VectorDerivativeFunctor with polynomial function
430 TEST(Chebyshev2, VectorDerivativeFunctor2) {
431  const size_t N = 64, M = 1, T = 15;
432  using VecD = Chebyshev2::VectorDerivativeFunctor;
433 
434  const Vector points = Chebyshev2::Points(N, 0, T);
435 
436  // Assign the parameter matrix 1xN
437  Matrix X(1, N);
438  for (size_t i = 0; i < N; ++i) {
439  X(i) = f(points(i));
440  }
441 
442  // Evaluate the derivative at the chebyshev points using
443  // VectorDerivativeFunctor.
444  for (size_t i = 0; i < N; ++i) {
445  VecD d(M, N, points(i), 0, T);
446  Vector1 Dx = d(X);
447  EXPECT_DOUBLES_EQUAL(fprime(points(i)), Dx(0), 1e-6);
448  }
449 
450  // Test Jacobian at the first chebyshev point.
451  Matrix actualH(M, M * N);
452  VecD vecd(M, N, points(0), 0, T);
453  vecd(X, actualH);
454  Matrix expectedH = numericalDerivative11<Vector1, Matrix, M * N>(
455  std::bind(&VecD::operator(), vecd, std::placeholders::_1, nullptr), X);
456  EXPECT(assert_equal(expectedH, actualH, 1e-6));
457 }
458 
459 //******************************************************************************
460 // Test ComponentDerivativeFunctor
461 TEST(Chebyshev2, ComponentDerivativeFunctor) {
462  const size_t N = 6, M = 2;
463  const double x = 0.2;
464  using CompFunc = Chebyshev2::ComponentDerivativeFunctor;
465  size_t row = 1;
466  CompFunc fx(M, N, row, x, 0, 3);
467  Matrix X = Matrix::Zero(M, N);
468  Matrix actualH(1, M * N);
469  EXPECT_DOUBLES_EQUAL(0, fx(X, actualH), 1e-8);
470 
471  Matrix expectedH = numericalDerivative11<double, Matrix, M * N>(
472  std::bind(&CompFunc::operator(), fx, std::placeholders::_1, nullptr), X);
473  EXPECT(assert_equal(expectedH, actualH, 1e-7));
474 }
475 
476 //******************************************************************************
477 TEST(Chebyshev2, IntegralWeights) {
478  const size_t N7 = 7;
479  Vector actual = Chebyshev2::IntegrationWeights(N7);
480  Vector expected = (Vector(N7) << 0.0285714285714286, 0.253968253968254,
481  0.457142857142857, 0.520634920634921, 0.457142857142857,
482  0.253968253968254, 0.0285714285714286)
483  .finished();
484  EXPECT(assert_equal(expected, actual));
485 
486  const size_t N8 = 8;
487  Vector actual2 = Chebyshev2::IntegrationWeights(N8);
488  Vector expected2 = (Vector(N8) << 0.0204081632653061, 0.190141007218208,
489  0.352242423718159, 0.437208405798326, 0.437208405798326,
490  0.352242423718159, 0.190141007218208, 0.0204081632653061)
491  .finished();
492  EXPECT(assert_equal(expected2, actual2));
493 }
494 
495 //******************************************************************************
496 int main() {
497  TestResult tr;
498  return TestRegistry::runAllTests(tr);
499 }
500 //******************************************************************************
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
Chebyshev2.h
Pseudo-spectral parameterization for Chebyshev polynomials of the second kind.
Pose2.h
2D Pose
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:43
TestHarness.h
x4
static string x4("x4")
fx
const double fx
Definition: testSmartStereoFactor_iSAM2.cpp:47
b
Scalar * b
Definition: benchVecAdd.cpp:17
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
main
int main()
Definition: testChebyshev2.cpp:496
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
X
#define X
Definition: icosphere.cpp:20
gtsam::FitBasis
Definition: FitBasis.h:52
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
x3
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
weights2
vector< double > weights2
Definition: testMFAS.cpp:32
gtsam::Chebyshev2
Definition: Chebyshev2.h:46
weights1
vector< double > weights1
Definition: testMFAS.cpp:30
sequence
Definition: pytypes.h:2146
fprime
double fprime(double x)
Definition: testChebyshev2.cpp:251
x1
Pose3 x1
Definition: testPose3.cpp:663
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
gtsam::Sequence
std::map< double, double > Sequence
Our sequence representation is a map of {x: y} values where y = f(x)
Definition: FitBasis.h:36
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
factorTesting.h
Evaluate derivatives of a nonlinear factor numerically.
Eigen::Triplet< double >
ceres::pow
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
f
double f(double x)
Definition: testChebyshev2.cpp:245
TEST
TEST(Chebyshev2, Point)
Definition: testChebyshev2.cpp:41
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
f3_at_6points
Vector6 f3_at_6points
Definition: testChebyshev2.cpp:364
proxy4
double proxy4(double x)
Definition: testChebyshev2.cpp:389
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam
traits
Definition: SFMdata.h:40
CHECK
#define CHECK(condition)
Definition: Test.h:108
row
m row(1)
std
Definition: BFloat16.h:88
FitBasis.h
Fit a Basis using least-squares.
gtsam::noiseModel::Diagonal::shared_ptr
std::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:321
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
N
#define N
Definition: igam.h:9
proxy3
double proxy3(double x)
Definition: testChebyshev2.cpp:365
align_3::t
Point2 t(10, 10)
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
R
Rot2 R(Rot2::fromAngle(0.1))
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam::Pose2
Definition: Pose2.h:39
gtsam::FitBasis::parameters
Parameters parameters() const
Return Fourier coefficients.
Definition: FitBasis.h:96
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:16:11