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
nonlinear
expressionTesting.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
20
#pragma once
21
22
#include <
gtsam/nonlinear/ExpressionFactor.h
>
23
#include <
gtsam/nonlinear/factorTesting.h
>
24
#include <
gtsam/base/Testable.h
>
25
26
namespace
gtsam
{
27
28
namespace
internal
{
29
// CPPUnitLite-style test for linearization of an ExpressionFactor
30
template
<
typename
T>
31
bool
testExpressionJacobians
(
const
std::string& name_,
32
const
gtsam::Expression<T>
& expression,
const
gtsam::Values
&
values
,
33
double
nd_step,
double
tolerance) {
34
// Create factor
35
size_t
size
=
traits<T>::dimension
;
36
ExpressionFactor<T>
f
(
noiseModel::Unit::Create
(
size
),
37
expression.
value
(
values
), expression);
38
return
testFactorJacobians
(name_,
f
,
values
, nd_step, tolerance);
39
}
40
}
// namespace internal
41
}
// namespace gtsam
42
48
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance) \
49
{ EXPECT(gtsam::internal::testExpressionJacobians(name_, expression, values, numerical_derivative_step, tolerance)); }
gtsam::Expression::value
T value(const Values &values, std::vector< Matrix > *H=nullptr) const
Return value and optional derivatives, reverse AD version Notes: this is not terribly efficient,...
Definition:
Expression-inl.h:143
Testable.h
Concept check for values that can be used in unit tests.
different_sigmas::values
HybridValues values
Definition:
testHybridBayesNet.cpp:247
size
Scalar Scalar int size
Definition:
benchVecAdd.cpp:17
gtsam::internal::testExpressionJacobians
bool testExpressionJacobians(const std::string &name_, const gtsam::Expression< T > &expression, const gtsam::Values &values, double nd_step, double tolerance)
Definition:
expressionTesting.h:31
gtsam::Expression
Definition:
Expression.h:49
gtsam::internal::testFactorJacobians
bool testFactorJacobians(const std::string &name_, const NoiseModelFactor &factor, const gtsam::Values &values, double delta, double tolerance)
Definition:
factorTesting.h:77
gtsam::noiseModel::Unit::Create
static shared_ptr Create(size_t dim)
Definition:
NoiseModel.h:631
factorTesting.h
Evaluate derivatives of a nonlinear factor numerically.
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition:
testExpression.cpp:218
gtsam
traits
Definition:
SFMdata.h:40
gtsam::traits
Definition:
Group.h:36
gtsam::Values
Definition:
Values.h:65
ExpressionFactor.h
internal
Definition:
BandTriangularSolver.h:13
gtsam::ExpressionFactor
Definition:
Expression.h:36
gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:40