Chebyshev2.h
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 
33 #pragma once
34 
35 #include <gtsam/base/Manifold.h>
37 #include <gtsam/basis/Basis.h>
38 
39 namespace gtsam {
40 
46 class GTSAM_EXPORT Chebyshev2 : public Basis<Chebyshev2> {
47  public:
49 
51  using Parameters = Eigen::Matrix<double, /*Nx1*/ -1, 1>;
52  using DiffMatrix = Eigen::Matrix<double, /*NxN*/ -1, -1>;
53 
64  static double Point(size_t N, int j, double a = -1, double b = 1);
65 
67  static Vector Points(size_t N) {
68  Vector points(N);
69  for (size_t j = 0; j < N; j++) {
70  points(j) = Point(N, j);
71  }
72  return points;
73  }
74 
76  static Vector Points(size_t N, double a, double b) {
77  Vector points = Points(N);
78  const double T1 = (a + b) / 2, T2 = (b - a) / 2;
79  points = T1 + (T2 * points).array();
80  return points;
81  }
82 
91  static Weights CalculateWeights(size_t N, double x, double a = -1,
92  double b = 1);
93 
98  static Weights DerivativeWeights(size_t N, double x, double a = -1,
99  double b = 1);
100 
105  static DiffMatrix DifferentiationMatrix(size_t N, double a = -1,
106  double b = 1);
107 
126  static Weights IntegrationWeights(size_t N, double a = -1, double b = 1);
127 
131  template <size_t M>
132  static Matrix matrix(std::function<Eigen::Matrix<double, M, 1>(double)> f,
133  size_t N, double a = -1, double b = 1) {
134  Matrix Xmat(M, N);
135  for (size_t j = 0; j < N; j++) {
136  Xmat.col(j) = f(Point(N, j, a, b));
137  }
138  return Xmat;
139  }
140 }; // \ Chebyshev2
141 
142 } // namespace gtsam
gtsam::Chebyshev2::matrix
static Matrix matrix(std::function< Eigen::Matrix< double, M, 1 >(double)> f, size_t N, double a=-1, double b=1)
Definition: Chebyshev2.h:132
array
int array[24]
Definition: Map_general_stride.cpp:1
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
gtsam::Basis
Definition: Basis.h:90
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::Chebyshev2
Definition: Chebyshev2.h:46
gtsam::Chebyshev2::Points
static Vector Points(size_t N)
All Chebyshev points.
Definition: Chebyshev2.h:67
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
Basis.h
Compute an interpolating basis.
Manifold.h
Base class and basic functions for Manifold types.
OptionalJacobian.h
Special class for optional Jacobian arguments.
T2
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:841
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::b
const G & b
Definition: Group.h:79
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam
traits
Definition: SFMdata.h:40
gtsam::Chebyshev2::Points
static Vector Points(size_t N, double a, double b)
All Chebyshev points, within [a,b] interval.
Definition: Chebyshev2.h:76
Eigen::Matrix< double, -1, 1 >
N
#define N
Definition: igam.h:9
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


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