Main Page
Related Pages
Modules
Namespaces
Namespace List
Namespace Members
All
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Functions
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Variables
_
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Typedefs
_
a
b
c
d
e
f
g
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
y
Enumerations
a
c
d
e
f
g
i
k
l
m
n
p
q
r
s
t
u
Enumerator
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
r
s
t
u
v
w
x
z
Classes
Class List
Class Hierarchy
Class Members
All
!
:
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
~
Functions
!
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
~
Variables
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Typedefs
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
z
Enumerations
a
b
c
d
f
k
l
m
n
o
p
r
s
t
v
z
Enumerator
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Related Functions
:
a
b
c
d
e
g
h
i
l
m
n
o
p
r
s
t
u
v
Files
File List
File Members
All
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Functions
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Variables
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
x
y
z
Typedefs
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
q
r
s
t
u
v
x
z
Enumerations
Enumerator
b
c
e
f
g
i
l
m
n
o
p
r
s
t
u
v
x
y
z
Macros
_
a
b
c
d
e
f
g
h
i
k
l
m
n
o
p
q
r
s
t
u
v
w
x
z
Examples
gtsam
basis
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
>
36
#include <
gtsam/base/OptionalJacobian.h
>
37
#include <
gtsam/basis/Basis.h
>
38
39
namespace
gtsam
{
40
46
class
GTSAM_EXPORT
Chebyshev2
:
public
Basis
<Chebyshev2> {
47
public
:
48
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
49
50
using
Base
=
Basis<Chebyshev2>
;
51
using
Parameters
=
Eigen::Matrix
<double,
/*Nx1*/
-1, 1>;
52
using
DiffMatrix
=
Eigen::Matrix
<double,
/*NxN*/
-1, -1>;
53
61
static
double
Point(
size_t
N
,
int
j
);
62
72
static
double
Point(
size_t
N
,
int
j
,
double
a
,
double
b
);
73
75
static
Vector
Points(
size_t
N
);
76
78
static
Vector
Points(
size_t
N
,
double
a
,
double
b
);
79
88
static
Weights
CalculateWeights(
size_t
N
,
double
x
,
double
a
= -1,
double
b
= 1);
89
94
static
Weights
DerivativeWeights(
size_t
N
,
double
x
,
double
a
= -1,
double
b
= 1);
95
100
static
DiffMatrix
DifferentiationMatrix(
size_t
N
);
101
103
static
DiffMatrix
DifferentiationMatrix(
size_t
N
,
double
a
,
double
b
);
104
107
static
Matrix
IntegrationMatrix(
size_t
N
);
108
110
static
Matrix
IntegrationMatrix(
size_t
N
,
double
a
,
double
b
);
111
117
static
Weights
IntegrationWeights(
size_t
N
);
118
120
static
Weights
IntegrationWeights(
size_t
N
,
double
a
,
double
b
);
121
127
static
Weights
DoubleIntegrationWeights(
size_t
N
);
128
130
static
Weights
DoubleIntegrationWeights(
size_t
N
,
double
a
,
double
b
);
131
133
static
Vector
vector(std::function<
double
(
double
)>
f
,
134
size_t
N
,
double
a
= -1,
double
b
= 1);
135
137
template
<
size_t
M>
138
static
Matrix
matrix
(std::function<
Eigen::Matrix<double, M, 1>
(
double
)>
f
,
139
size_t
N
,
double
a
= -1,
double
b
= 1) {
140
Matrix
Xmat(
M
,
N
);
141
const
Vector
points = Points(
N
,
a
,
b
);
142
for
(
size_t
j
= 0;
j
<
N
;
j
++) Xmat.col(
j
) =
f
(points(
j
));
143
return
Xmat;
144
}
145
};
// \ Chebyshev2
146
147
}
// 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)
Create matrix of values at Chebyshev points given vector-valued function.
Definition:
Chebyshev2.h:138
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
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.
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
Eigen::Matrix< double, -1, 1 >
N
#define N
Definition:
igam.h:9
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition:
bench_gemm.cpp:51
gtsam
Author(s):
autogenerated on Fri Mar 28 2025 03:01:13