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 gtsam;
32 
33 //******************************************************************************
34 TEST(Chebyshev2, Point) {
35  static const size_t N = 5;
36  auto points = Chebyshev2::Points(N);
37  Vector expected(N);
38  expected << -1., -sqrt(2.) / 2., 0., sqrt(2.) / 2., 1.;
39  static const double tol = 1e-15; // changing this reveals errors
40  EXPECT_DOUBLES_EQUAL(expected(0), points(0), tol);
41  EXPECT_DOUBLES_EQUAL(expected(1), points(1), tol);
42  EXPECT_DOUBLES_EQUAL(expected(2), points(2), tol);
43  EXPECT_DOUBLES_EQUAL(expected(3), points(3), tol);
44  EXPECT_DOUBLES_EQUAL(expected(4), points(4), tol);
45 
46  // Check symmetry
49 }
50 
51 //******************************************************************************
52 TEST(Chebyshev2, PointInInterval) {
53  static const size_t N = 5;
54  auto points = Chebyshev2::Points(N, 0, 20);
55  Vector expected(N);
56  expected << 0., 1. - sqrt(2.) / 2., 1., 1. + sqrt(2.) / 2., 2.;
57  expected *= 10.0;
58  static const double tol = 1e-15; // changing this reveals errors
59  EXPECT_DOUBLES_EQUAL(expected(0), points(0), tol);
60  EXPECT_DOUBLES_EQUAL(expected(1), points(1), tol);
61  EXPECT_DOUBLES_EQUAL(expected(2), points(2), tol);
62  EXPECT_DOUBLES_EQUAL(expected(3), points(3), tol);
63  EXPECT_DOUBLES_EQUAL(expected(4), points(4), tol);
64 
65  // all at once
66  Vector actual = Chebyshev2::Points(N, 0, 20);
67  CHECK(assert_equal(expected, actual));
68 }
69 
70 //******************************************************************************
71 // InterpolatingPolynomial[{{-1, 4}, {0, 2}, {1, 6}}, 0.5]
72 TEST(Chebyshev2, Interpolate2) {
73  const size_t N = 3;
74  Chebyshev2::EvaluationFunctor fx(N, 0.5);
75  Vector f(N);
76  f << 4, 2, 6;
77  EXPECT_DOUBLES_EQUAL(3.25, fx(f), 1e-9);
78 }
79 
80 //******************************************************************************
81 // InterpolatingPolynomial[{{0, 4}, {1, 2}, {2, 6}}, 1.5]
82 TEST(Chebyshev2, Interpolate2_Interval) {
83  Chebyshev2::EvaluationFunctor fx(3, 1.5, 0, 2);
84  Vector3 f(4, 2, 6);
85  EXPECT_DOUBLES_EQUAL(3.25, fx(f), 1e-9);
86 }
87 
88 //******************************************************************************
89 // InterpolatingPolynomial[{{-1, 4}, {-Sqrt[2]/2, 2}, {0, 6}, {Sqrt[2]/2,3}, {1,
90 // 3}}, 0.5]
91 TEST(Chebyshev2, Interpolate5) {
92  Chebyshev2::EvaluationFunctor fx(5, 0.5);
93  Vector f(5);
94  f << 4, 2, 6, 3, 3;
95  EXPECT_DOUBLES_EQUAL(4.34283, fx(f), 1e-5);
96 }
97 
98 //******************************************************************************
99 // Interpolating vectors
100 TEST(Chebyshev2, InterpolateVector) {
101  double t = 30, a = 0, b = 100;
102  const size_t N = 3;
103  // Create 2x3 matrix with Vectors at Chebyshev points
104  Matrix X = Matrix::Zero(2, N);
105  X.row(0) = Chebyshev2::Points(N, a, b); // slope 1 ramp
106 
107  // Check value
108  Vector expected(2);
109  expected << t, 0;
110  Eigen::Matrix<double, /*2x2N*/ -1, -1> actualH(2, 2 * N);
111 
112  Chebyshev2::VectorEvaluationFunctor fx(2, N, t, a, b);
113  EXPECT(assert_equal(expected, fx(X, actualH), 1e-9));
114 
115  // Check derivative
116  std::function<Vector2(Matrix)> f =
117  std::bind(&Chebyshev2::VectorEvaluationFunctor::operator(), fx,
118  std::placeholders::_1, nullptr);
119  Matrix numericalH =
120  numericalDerivative11<Vector2, Matrix, 2 * N>(f, X);
121  EXPECT(assert_equal(numericalH, actualH, 1e-9));
122 }
123 
124 //******************************************************************************
125 // Interpolating poses using the exponential map
126 TEST(Chebyshev2, InterpolatePose2) {
127  const size_t N = 32;
128  double t = 30, a = 0, b = 100;
129 
130  Matrix X(3, N);
131  X.row(0) = Chebyshev2::Points(N, a, b); // slope 1 ramp
132  X.row(1) = Vector::Zero(N);
133  X.row(2) = 0.1 * Vector::Ones(N);
134 
135  Vector xi(3);
136  xi << t, 0, 0.1;
137  Eigen::Matrix<double, /*3x3N*/ -1, -1> actualH(3, 3 * N);
138 
139  Chebyshev2::ManifoldEvaluationFunctor<Pose2> fx(N, t, a, b);
140  // We use xi as canonical coordinates via exponential map
142  EXPECT(assert_equal(expected, fx(X, actualH)));
143 
144  // Check derivative
145  std::function<Pose2(Matrix)> f =
146  std::bind(&Chebyshev2::ManifoldEvaluationFunctor<Pose2>::operator(), fx,
147  std::placeholders::_1, nullptr);
148  Matrix numericalH =
149  numericalDerivative11<Pose2, Matrix, 3 * N>(f, X);
150  EXPECT(assert_equal(numericalH, actualH, 1e-9));
151 }
152 
153 #ifdef GTSAM_POSE3_EXPMAP
154 //******************************************************************************
155 // Interpolating poses using the exponential map
156 TEST(Chebyshev2, InterpolatePose3) {
157  const size_t N = 32;
158  double a = 10, b = 100;
159  double t = Chebyshev2::Points(N, a, b)(11);
160 
161  Rot3 R = Rot3::Ypr(-2.21366492e-05, -9.35353636e-03, -5.90463598e-04);
162  Pose3 pose(R, Point3(1, 2, 3));
163 
165  Eigen::Matrix<double, /*6x6N*/ -1, -1> actualH(6, 6 * N);
166 
167  Matrix X = Matrix::Zero(6, N);
168  X.col(11) = xi;
169 
170  Chebyshev2::ManifoldEvaluationFunctor<Pose3> fx(N, t, a, b);
171  // We use xi as canonical coordinates via exponential map
173  EXPECT(assert_equal(expected, fx(X, actualH)));
174 
175  // Check derivative
176  std::function<Pose3(Matrix)> f =
177  std::bind(&Chebyshev2::ManifoldEvaluationFunctor<Pose3>::operator(), fx,
178  std::placeholders::_1, nullptr);
179  Matrix numericalH =
180  numericalDerivative11<Pose3, Matrix, 6 * N>(f, X);
181  EXPECT(assert_equal(numericalH, actualH, 1e-8));
182 }
183 #endif
184 
185 //******************************************************************************
186 TEST(Chebyshev2, Decomposition) {
187  // Create example sequence
189  for (size_t i = 0; i < 16; i++) {
190  double x = (1.0 / 16) * i - 0.99, y = x;
191  sequence[x] = y;
192  }
193 
194  // Do Chebyshev Decomposition
195  FitBasis<Chebyshev2> actual(sequence, nullptr, 3);
196 
197  // Check
198  Vector expected(3);
199  expected << -1, 0, 1;
200  EXPECT(assert_equal(expected, actual.parameters(), 1e-4));
201 }
202 
203 //******************************************************************************
204 TEST(Chebyshev2, DifferentiationMatrix3) {
205  // Trefethen00book, p.55
206  const size_t N = 3;
207  Matrix expected(N, N);
208  // Differentiation matrix computed from chebfun
209  expected << 1.5000, -2.0000, 0.5000, //
210  0.5000, -0.0000, -0.5000, //
211  -0.5000, 2.0000, -1.5000;
212  // multiply by -1 since the chebyshev points have a phase shift wrt Trefethen
213  // This was verified with chebfun
214  expected = -expected;
215 
217  EXPECT(assert_equal(expected, actual, 1e-4));
218 }
219 
220 //******************************************************************************
221 TEST(Chebyshev2, DerivativeMatrix6) {
222  // Trefethen00book, p.55
223  const size_t N = 6;
224  Matrix expected(N, N);
225  expected << 8.5000, -10.4721, 2.8944, -1.5279, 1.1056, -0.5000, //
226  2.6180, -1.1708, -2.0000, 0.8944, -0.6180, 0.2764, //
227  -0.7236, 2.0000, -0.1708, -1.6180, 0.8944, -0.3820, //
228  0.3820, -0.8944, 1.6180, 0.1708, -2.0000, 0.7236, //
229  -0.2764, 0.6180, -0.8944, 2.0000, 1.1708, -2.6180, //
230  0.5000, -1.1056, 1.5279, -2.8944, 10.4721, -8.5000;
231  // multiply by -1 since the chebyshev points have a phase shift wrt Trefethen
232  // This was verified with chebfun
233  expected = -expected;
234 
236  EXPECT(assert_equal((Matrix)expected, actual, 1e-4));
237 }
238 
239 // test function for CalculateWeights and DerivativeWeights
240 double f(double x) {
241  // return 3*(x**3) - 2*(x**2) + 5*x - 11
242  return 3.0 * pow(x, 3) - 2.0 * pow(x, 2) + 5.0 * x - 11;
243 }
244 
245 // its derivative
246 double fprime(double x) {
247  // return 9*(x**2) - 4*(x) + 5
248  return 9.0 * pow(x, 2) - 4.0 * x + 5.0;
249 }
250 
251 //******************************************************************************
252 TEST(Chebyshev2, CalculateWeights) {
253  const size_t N = 32;
254  Vector fvals = Chebyshev2::vector(f, N);
255  double x1 = 0.7, x2 = -0.376;
258  EXPECT_DOUBLES_EQUAL(f(x1), weights1 * fvals, 1e-8);
259  EXPECT_DOUBLES_EQUAL(f(x2), weights2 * fvals, 1e-8);
260 }
261 
262 TEST(Chebyshev2, CalculateWeights2) {
263  const size_t N = 32;
264  double a = 0, b = 10, x1 = 7, x2 = 4.12;
265  Vector fvals = Chebyshev2::vector(f, N, a, b);
266 
268  EXPECT_DOUBLES_EQUAL(f(x1), weights1 * fvals, 1e-8);
269 
271  double expected2 = f(x2); // 185.454784
272  double actual2 = weights2 * fvals;
273  EXPECT_DOUBLES_EQUAL(expected2, actual2, 1e-8);
274 }
275 
276 // Test CalculateWeights when a point coincides with a Chebyshev point
277 TEST(Chebyshev2, CalculateWeights_CoincidingPoint) {
278  const size_t N = 5;
279  const double coincidingPoint = Chebyshev2::Point(N, 1); // Pick the 2nd point
280 
281  // Generate weights for the coinciding point
282  Weights weights = Chebyshev2::CalculateWeights(N, coincidingPoint);
283 
284  // Verify that the weights are zero everywhere except at the coinciding point
285  for (size_t j = 0; j < N; ++j) {
286  EXPECT_DOUBLES_EQUAL(j == 1 ? 1.0 : 0.0, weights(j), 1e-9);
287  }
288 }
289 
290 TEST(Chebyshev2, DerivativeWeights) {
291  const size_t N = 32;
292  Vector fvals = Chebyshev2::vector(f, N);
293  std::vector<double> testPoints = { 0.7, -0.376, 0.0 };
294  for (double x : testPoints) {
296  EXPECT_DOUBLES_EQUAL(fprime(x), dWeights * fvals, 1e-9);
297  }
298 
299  // test if derivative calculation at Chebyshev point is correct
300  double x4 = Chebyshev2::Point(N, 3);
302  EXPECT_DOUBLES_EQUAL(fprime(x4), dWeights4 * fvals, 1e-9);
303 }
304 
305 TEST(Chebyshev2, DerivativeWeights2) {
306  const size_t N = 32;
307  double x1 = 5, x2 = 4.12, a = 0, b = 10;
308  Vector fvals = Chebyshev2::vector(f, N, a, b);
309 
310  Weights dWeights1 = Chebyshev2::DerivativeWeights(N, x1, a, b);
311  EXPECT_DOUBLES_EQUAL(fprime(x1), dWeights1 * fvals, 1e-8);
312 
313  Weights dWeights2 = Chebyshev2::DerivativeWeights(N, x2, a, b);
314  EXPECT_DOUBLES_EQUAL(fprime(x2), dWeights2 * fvals, 1e-8);
315 
316  // test if derivative calculation at Chebyshev point is correct
317  double x3 = Chebyshev2::Point(N, 3, a, b);
318  Weights dWeights3 = Chebyshev2::DerivativeWeights(N, x3, a, b);
319  EXPECT_DOUBLES_EQUAL(fprime(x3), dWeights3 * fvals, 1e-8);
320 }
321 
322 
323 //******************************************************************************
324 // Check two different ways to calculate the derivative weights
325 TEST(Chebyshev2, DerivativeWeightsDifferentiationMatrix) {
326  const size_t N6 = 6;
327  double x1 = 0.311;
331  EXPECT(assert_equal(expected, actual, 1e-12));
332 
333  double a = -3, b = 8, x2 = 5.05;
335  Weights expected1 = Chebyshev2::CalculateWeights(N6, x2, a, b) * D6_2;
336  Weights actual1 = Chebyshev2::DerivativeWeights(N6, x2, a, b);
337  EXPECT(assert_equal(expected1, actual1, 1e-12));
338 }
339 
340 //******************************************************************************
341 // Check two different ways to calculate the derivative weights
342 TEST(Chebyshev2, DerivativeWeights6) {
343  const size_t N6 = 6;
345  Chebyshev2::Parameters x = Chebyshev2::Points(N6); // ramp with slope 1
346  EXPECT(assert_equal(Vector::Ones(N6), Vector(D6 * x)));
347 }
348 
349 //******************************************************************************
350 // Check two different ways to calculate the derivative weights
351 TEST(Chebyshev2, DerivativeWeights7) {
352  const size_t N7 = 7;
354  Chebyshev2::Parameters x = Chebyshev2::Points(N7); // ramp with slope 1
355  EXPECT(assert_equal(Vector::Ones(N7), Vector(D7 * x)));
356 }
357 
358 //******************************************************************************
359 // Check derivative in two different ways: numerical and using D on f
360 Vector6 f3_at_6points = (Vector6() << 4, 2, 6, 2, 4, 3).finished();
361 double proxy3(double x) {
362  return Chebyshev2::EvaluationFunctor(6, x)(f3_at_6points);
363 }
364 
365 // Check Derivative evaluation at point x=0.2
366 TEST(Chebyshev2, Derivative6) {
367  // calculate expected values by numerical derivative of synthesis
368  const double x = 0.2;
369  Matrix numeric_dTdx = numericalDerivative11<double, double>(proxy3, x);
370 
371  // Calculate derivatives at Chebyshev points using D3, interpolate
373  Vector derivative_at_points = D6 * f3_at_6points;
374  Chebyshev2::EvaluationFunctor fx(6, x);
375  EXPECT_DOUBLES_EQUAL(numeric_dTdx(0, 0), fx(derivative_at_points), 1e-8);
376 
377  // Do directly
378  Chebyshev2::DerivativeFunctor dfdx(6, x);
379  EXPECT_DOUBLES_EQUAL(numeric_dTdx(0, 0), dfdx(f3_at_6points), 1e-8);
380 }
381 
382 //******************************************************************************
383 // Assert that derivative also works in non-standard interval [0,3]
384 double proxy4(double x) {
385  return Chebyshev2::EvaluationFunctor(6, x, 0, 3)(f3_at_6points);
386 }
387 
388 TEST(Chebyshev2, Derivative6_03) {
389  // Check Derivative evaluation at point x=0.2, in interval [0,3]
390 
391  // calculate expected values by numerical derivative of synthesis
392  const double x = 0.2;
393  Matrix numeric_dTdx = numericalDerivative11<double, double>(proxy4, x);
394 
395  // Calculate derivatives at Chebyshev points using D3, interpolate
397  Vector derivative_at_points = D6 * f3_at_6points;
398  Chebyshev2::EvaluationFunctor fx(6, x, 0, 3);
399  EXPECT_DOUBLES_EQUAL(numeric_dTdx(0, 0), fx(derivative_at_points), 1e-8);
400 
401  // Do directly
402  Chebyshev2::DerivativeFunctor dfdx(6, x, 0, 3);
403  EXPECT_DOUBLES_EQUAL(numeric_dTdx(0, 0), dfdx(f3_at_6points), 1e-8);
404 }
405 
406 //******************************************************************************
407 // Test VectorDerivativeFunctor
408 TEST(Chebyshev2, VectorDerivativeFunctor) {
409  const size_t N = 3, M = 2;
410  const double x = 0.2;
411  using VecD = Chebyshev2::VectorDerivativeFunctor;
412  VecD fx(M, N, x, 0, 3);
413  Matrix X = Matrix::Zero(M, N);
414  Matrix actualH(M, M * N);
415  EXPECT(assert_equal(Vector::Zero(M), (Vector)fx(X, actualH), 1e-8));
416 
417  // Test Jacobian
418  Matrix expectedH = numericalDerivative11<Vector2, Matrix, M* N>(
419  std::bind(&VecD::operator(), fx, std::placeholders::_1, nullptr), X);
420  EXPECT(assert_equal(expectedH, actualH, 1e-7));
421 }
422 
423 //******************************************************************************
424 // Test VectorDerivativeFunctor with polynomial function
425 TEST(Chebyshev2, VectorDerivativeFunctor2) {
426  const size_t N = 4, M = 1, T = 15;
427  using VecD = Chebyshev2::VectorDerivativeFunctor;
428 
429  const Vector points = Chebyshev2::Points(N, 0, T);
430 
431  // Assign the parameter matrix 1xN
432  Matrix X(1, N);
433  for (size_t i = 0; i < N; ++i) {
434  X(i) = f(points(i));
435  }
436 
437  // Evaluate the derivative at the chebyshev points using
438  // VectorDerivativeFunctor.
439  for (size_t i = 0; i < N; ++i) {
440  VecD d(M, N, points(i), 0, T);
441  Vector1 Dx = d(X);
442  EXPECT_DOUBLES_EQUAL(fprime(points(i)), Dx(0), 1e-6);
443  }
444 
445  // Test Jacobian at the first chebyshev point.
446  Matrix actualH(M, M * N);
447  VecD vecd(M, N, points(0), 0, T);
448  vecd(X, actualH);
449  Matrix expectedH = numericalDerivative11<Vector1, Matrix, M* N>(
450  std::bind(&VecD::operator(), vecd, std::placeholders::_1, nullptr), X);
451  EXPECT(assert_equal(expectedH, actualH, 1e-6));
452 }
453 
454 //******************************************************************************
455 // Test ComponentDerivativeFunctor
456 TEST(Chebyshev2, ComponentDerivativeFunctor) {
457  const size_t N = 6, M = 2;
458  const double x = 0.2;
459  using CompFunc = Chebyshev2::ComponentDerivativeFunctor;
460  size_t row = 1;
461  CompFunc fx(M, N, row, x, 0, 3);
462  Matrix X = Matrix::Zero(M, N);
463  Matrix actualH(1, M * N);
464  EXPECT_DOUBLES_EQUAL(0, fx(X, actualH), 1e-8);
465 
466  Matrix expectedH = numericalDerivative11<double, Matrix, M* N>(
467  std::bind(&CompFunc::operator(), fx, std::placeholders::_1, nullptr), X);
468  EXPECT(assert_equal(expectedH, actualH, 1e-7));
469 }
470 
471 //******************************************************************************
472 TEST(Chebyshev2, IntegrationMatrix) {
473  const size_t N = 10; // number of intervals => N+1 nodes
474  const double a = 0, b = 10;
475 
476  // Create integration matrix
478 
479  // Let's check that integrating a constant yields
480  // the sum of the lengths of the intervals:
481  Vector F = P * Vector::Ones(N);
482  EXPECT_DOUBLES_EQUAL(0, F(0), 1e-9); // check first value is 0
483  Vector points = Chebyshev2::Points(N, a, b);
484  Vector ramp(N);
485  for (size_t i = 0; i < N; ++i) ramp(i) = points(i) - a;
486  EXPECT(assert_equal(ramp, F, 1e-9));
487 
488  // Get values of the derivative (fprime) at the Chebyshev nodes
489  Vector fp = Chebyshev2::vector(fprime, N, a, b);
490 
491  // Integrate to get back f, using the integration matrix.
492  // Since there is a constant term, we need to add it back.
493  Vector F_est = P * fp;
494  EXPECT_DOUBLES_EQUAL(0, F_est(0), 1e-9); // check first value is 0
495 
496  // For comparison, get actual function values at the nodes
497  Vector F_true = Chebyshev2::vector(f, N, a, b);
498 
499  // Verify the integration matrix worked correctly, after adding back the
500  // constant term
501  F_est.array() += f(a);
502  EXPECT(assert_equal(F_true, F_est, 1e-9));
503 
504  // Differentiate the result to get back to our derivative function
506  Vector ff_est = D * F_est;
507 
508  // Verify the round trip worked
509  EXPECT(assert_equal(fp, ff_est, 1e-9));
510 }
511 
512 //******************************************************************************
513 TEST(Chebyshev2, IntegrationWeights7) {
514  const size_t N = 7;
515  Weights actual = Chebyshev2::IntegrationWeights(N, -1, 1);
516 
517  // Expected values were calculated using chebfun:
518  Weights expected = (Weights(N) << 0.0285714285714286, 0.253968253968254,
519  0.457142857142857, 0.520634920634921, 0.457142857142857,
520  0.253968253968254, 0.0285714285714286)
521  .finished();
522  EXPECT(assert_equal(expected, actual));
523 
524  // Assert that multiplying with all ones gives the correct integral (2.0)
525  EXPECT_DOUBLES_EQUAL(2.0, actual.array().sum(), 1e-9);
526 
527  // Integrating f' over [-1,1] should give f(1) - f(-1)
529  double expectedF = f(1) - f(-1);
530  double actualW = actual * fp;
531  EXPECT_DOUBLES_EQUAL(expectedF, actualW, 1e-9);
532 
533  // We can calculate an alternate set of weights using the integration matrix:
535  Weights p7 = P.row(N-1);
536 
537  // Check that the two sets of weights give the same results
538  EXPECT_DOUBLES_EQUAL(expectedF, p7 * fp, 1e-9);
539 
540  // And same for integrate f itself:
541  Vector fvals = Chebyshev2::vector(f, N);
542  EXPECT_DOUBLES_EQUAL(p7*fvals, actual * fvals, 1e-9);
543 }
544 
545 // Check N=8
546 TEST(Chebyshev2, IntegrationWeights8) {
547  const size_t N = 8;
548  Weights actual = Chebyshev2::IntegrationWeights(N, -1, 1);
549  Weights expected = (Weights(N) << 0.0204081632653061, 0.190141007218208,
550  0.352242423718159, 0.437208405798326, 0.437208405798326,
551  0.352242423718159, 0.190141007218208, 0.0204081632653061)
552  .finished();
553  EXPECT(assert_equal(expected, actual));
554  EXPECT_DOUBLES_EQUAL(2.0, actual.array().sum(), 1e-9);
555 }
556 
557 //******************************************************************************
558 TEST(Chebyshev2, DoubleIntegrationWeights) {
559  const size_t N = 7;
560  const double a = 0, b = 10;
561  // Let's integrate constant twice get a test case:
563  auto ones = Vector::Ones(N);
564 
565  // Check the sum which should be 0.5*t^2 | [0,b] = b^2/2:
567  EXPECT_DOUBLES_EQUAL(b*b/2, w * ones, 1e-9);
568 }
569 
570 TEST(Chebyshev2, DoubleIntegrationWeights2) {
571  const size_t N = 8;
572  const double a = 0, b = 3;
573  // Let's integrate constant twice get a test case:
575  auto ones = Vector::Ones(N);
576 
577  // Check the sum which should be 0.5*t^2 | [0,b] = b^2/2:
579  EXPECT_DOUBLES_EQUAL(b*b/2, w * ones, 1e-9);
580 }
581 
582 //******************************************************************************
583 int main() {
584  TestResult tr;
585  return TestRegistry::runAllTests(tr);
586 }
587 //******************************************************************************
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
Chebyshev2.h
Pseudo-spectral parameterization for Chebyshev polynomials of the second kind.
Pose2.h
2D Pose
D
MatrixXcd D
Definition: EigenSolver_EigenSolver_MatrixType.cpp:14
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:169
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
gtsam::Chebyshev2::DifferentiationMatrix
static DiffMatrix DifferentiationMatrix(size_t N)
Definition: Chebyshev2.cpp:202
TestHarness.h
x4
static string x4("x4")
gtsam::Chebyshev2::IntegrationMatrix
static Matrix IntegrationMatrix(size_t N)
Definition: Chebyshev2.cpp:227
fx
const double fx
Definition: testSmartStereoFactor_iSAM2.cpp:47
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:583
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::Pose2::ChartAtOrigin::Retract
static Pose2 Retract(const Vector3 &v, ChartJacobian H={})
Definition: Pose2.cpp:100
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::Rot3::Ypr
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hp={}, OptionalJacobian< 3, 1 > Hr={})
Definition: Rot3.h:200
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:2148
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
fprime
double fprime(double x)
Definition: testChebyshev2.cpp:246
gtsam::row
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:215
x1
Pose3 x1
Definition: testPose3.cpp:692
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
gtsam::Weights
Eigen::Matrix< double, 1, -1 > Weights
Definition: Basis.h:69
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:916
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
gtsam::Pose3::ChartAtOrigin::Retract
static Pose3 Retract(const Vector6 &xi, ChartJacobian Hxi={})
Definition: Pose3.cpp:281
gtsam::symbol_shorthand::F
Key F(std::uint64_t j)
Definition: inference/Symbol.h:153
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
f
double f(double x)
Definition: testChebyshev2.cpp:240
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
gtsam::Chebyshev2::IntegrationWeights
static Weights IntegrationWeights(size_t N)
Definition: Chebyshev2.cpp:264
f3_at_6points
Vector6 f3_at_6points
Definition: testChebyshev2.cpp:360
gtsam::b
const G & b
Definition: Group.h:79
proxy4
double proxy4(double x)
Definition: testChebyshev2.cpp:384
gtsam::Pose3::ChartAtOrigin::Local
static Vector6 Local(const Pose3 &pose, ChartJacobian Hpose={})
Definition: Pose3.cpp:296
gtsam::Chebyshev2::CalculateWeights
static Weights CalculateWeights(size_t N, double x, double a=-1, double b=1)
Definition: Chebyshev2.cpp:121
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam
traits
Definition: SFMdata.h:40
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
CHECK
#define CHECK(condition)
Definition: Test.h:108
FitBasis.h
Fit a Basis using least-squares.
gtsam::Chebyshev2::Points
static Vector Points(size_t N)
All Chebyshev points.
Definition: Chebyshev2.cpp:39
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
P
static double P[]
Definition: ellpe.c:68
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:361
ramp
double ramp(double x)
Definition: class_CwiseUnaryOp_ptrfun.cpp:7
align_3::t
Point2 t(10, 10)
gtsam::Chebyshev2::DoubleIntegrationWeights
static Weights DoubleIntegrationWeights(size_t N)
Definition: Chebyshev2.cpp:293
gtsam::Chebyshev2::vector
static Vector vector(std::function< double(double)> f, size_t N, double a=-1, double b=1)
Create matrix of values at Chebyshev points given vector-valued function.
Definition: Chebyshev2.cpp:306
gtsam::Chebyshev2::Point
static double Point(size_t N, int j)
Specific Chebyshev point, within [-1,1] interval.
Definition: Chebyshev2.cpp:27
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
gtsam::Chebyshev2::DerivativeWeights
static Weights DerivativeWeights(size_t N, double x, double a=-1, double b=1)
Definition: Chebyshev2.cpp:151
R
Rot2 R(Rot2::fromAngle(0.1))
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
ones
MatrixXcf ones
Definition: ComplexEigenSolver_eigenvalues.cpp:1
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 Fri Mar 28 2025 03:06:42