#include <Chebyshev2.h>
Public Types | |
using | Base = Basis< Chebyshev2 > |
using | DiffMatrix = Eigen::Matrix< double, -1, -1 > |
using | Parameters = Eigen::Matrix< double, -1, 1 > |
Static Public Member Functions | |
static Weights | CalculateWeights (size_t N, double x, double a=-1, double b=1) |
static Weights | DerivativeWeights (size_t N, double x, double a=-1, double b=1) |
static DiffMatrix | DifferentiationMatrix (size_t N) |
static DiffMatrix | DifferentiationMatrix (size_t N, double a, double b) |
Compute D = differentiation matrix, for interval [a,b]. More... | |
static Weights | DoubleIntegrationWeights (size_t N) |
static Weights | DoubleIntegrationWeights (size_t N, double a, double b) |
Calculate Double Clenshaw-Curtis integration weights, for interval [a,b]. More... | |
static Matrix | IntegrationMatrix (size_t N) |
static Matrix | IntegrationMatrix (size_t N, double a, double b) |
IntegrationMatrix returns the (N+1)×(N+1) matrix P for interval [a,b]. More... | |
static Weights | IntegrationWeights (size_t N) |
static Weights | IntegrationWeights (size_t N, double a, double b) |
Calculate Clenshaw-Curtis integration weights, for interval [a,b]. More... | |
template<size_t M> | |
static Matrix | matrix (std::function< Eigen::Matrix< double, M, 1 >(double)> f, size_t N, double a=-1, double b=1) |
Create matrix of values at Chebyshev points given vector-valued function. More... | |
static double | Point (size_t N, int j) |
Specific Chebyshev point, within [-1,1] interval. More... | |
static double | Point (size_t N, int j, double a, double b) |
Specific Chebyshev point, within [a,b] interval. More... | |
static Vector | Points (size_t N) |
All Chebyshev points. More... | |
static Vector | Points (size_t N, double a, double b) |
All Chebyshev points, within [a,b] interval. More... | |
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. More... | |
![]() | |
static Matrix | WeightMatrix (size_t N, const Vector &X) |
static Matrix | WeightMatrix (size_t N, const Vector &X, double a, double b) |
Calculate weights for all x in vector X, with interval [a,b]. More... | |
Chebyshev Interpolation on Chebyshev points of the second kind Note that N here, the number of points, is one less than N from 'Approximation Theory and Approximation Practice by L. N. Trefethen (pg.42)'.
Definition at line 46 of file Chebyshev2.h.
using gtsam::Chebyshev2::Base = Basis<Chebyshev2> |
Definition at line 50 of file Chebyshev2.h.
using gtsam::Chebyshev2::DiffMatrix = Eigen::Matrix<double, -1, -1> |
Definition at line 52 of file Chebyshev2.h.
using gtsam::Chebyshev2::Parameters = Eigen::Matrix<double, -1, 1> |
Definition at line 51 of file Chebyshev2.h.
|
static |
Evaluate Chebyshev Weights on [-1,1] at any x up to order N-1 (N values) These weights implement barycentric interpolation at a specific x. More precisely, f(x) ~ [w0;...;wN] * [f0;...;fN], where the fj are the values of the function f at the Chebyshev points. As such, for a given x we obtain a linear map from parameter vectors f to interpolated values f(x). Optional [a,b] interval can be specified as well.
Definition at line 121 of file Chebyshev2.cpp.
|
static |
Evaluate derivative of barycentric weights. This is easy and efficient via the DifferentiationMatrix.
Definition at line 151 of file Chebyshev2.cpp.
|
static |
Compute D = differentiation matrix, Trefethen00book p.53 When given a parameter vector f of function values at the Chebyshev points, D*f are the values of f'. https://people.maths.ox.ac.uk/trefethen/8all.pdf Theorem 8.4
Definition at line 202 of file Chebyshev2.cpp.
|
static |
Compute D = differentiation matrix, for interval [a,b].
Definition at line 216 of file Chebyshev2.cpp.
Calculate Double Clenshaw-Curtis integration weights We compute them as W * P, where W are the Clenshaw-Curtis weights and P is the integration matrix.
Definition at line 293 of file Chebyshev2.cpp.
Calculate Double Clenshaw-Curtis integration weights, for interval [a,b].
Definition at line 299 of file Chebyshev2.cpp.
IntegrationMatrix returns the (N+1)×(N+1) matrix P such that for any f, F = P * f recovers F (the antiderivative) satisfying f = D * F and F(0)=0.
Definition at line 227 of file Chebyshev2.cpp.
IntegrationMatrix returns the (N+1)×(N+1) matrix P for interval [a,b].
Definition at line 244 of file Chebyshev2.cpp.
Calculate Clenshaw-Curtis integration weights. Trefethen00book, pg 128, clencurt.m Note that N in clencurt.m is 1 less than our N
Definition at line 264 of file Chebyshev2.cpp.
Calculate Clenshaw-Curtis integration weights, for interval [a,b].
Definition at line 289 of file Chebyshev2.cpp.
|
inlinestatic |
Create matrix of values at Chebyshev points given vector-valued function.
Definition at line 138 of file Chebyshev2.h.
Specific Chebyshev point, within [-1,1] interval.
N | The degree of the polynomial |
j | The index of the Chebyshev point |
Definition at line 27 of file Chebyshev2.cpp.
Specific Chebyshev point, within [a,b] interval.
N | The degree of the polynomial |
j | The index of the Chebyshev point |
a | Lower bound of interval (default: -1) |
b | Upper bound of interval (default: 1) |
Definition at line 34 of file Chebyshev2.cpp.
All Chebyshev points.
Definition at line 39 of file Chebyshev2.cpp.
All Chebyshev points, within [a,b] interval.
Definition at line 58 of file Chebyshev2.cpp.
|
static |
Create matrix of values at Chebyshev points given vector-valued function.
Create vector of values at Chebyshev points given scalar-valued function.
Definition at line 306 of file Chebyshev2.cpp.