testBasisFactors.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  * -------------------------------1-------------------------------------------
11  */
12 
21 #include <gtsam/base/Testable.h>
23 #include <gtsam/base/Vector.h>
24 #include <gtsam/basis/Basis.h>
26 #include <gtsam/basis/Chebyshev2.h>
27 #include <gtsam/geometry/Pose2.h>
28 #include <gtsam/inference/Symbol.h>
32 
33 using gtsam::Chebyshev2;
38 using gtsam::Pose2;
39 using gtsam::Values;
40 using gtsam::Vector;
42 
43 constexpr size_t N = 2;
44 
45 // Key used in all tests
46 const gtsam::Symbol key('X', 0);
47 
48 //******************************************************************************
49 TEST(BasisFactors, EvaluationFactor) {
51 
52  double measured = 0;
53 
54  auto model = Isotropic::Sigma(1, 1.0);
55  EvaluationFactor<Chebyshev2> factor(key, measured, model, N, 0);
56 
58  graph.add(factor);
59 
60  Vector functionValues(N);
61  functionValues.setZero();
62 
64  initial.insert<Vector>(key, functionValues);
65 
67  parameters.setMaxIterations(20);
68  Values result =
70 
72 }
73 
74 //******************************************************************************
75 TEST(BasisFactors, VectorEvaluationFactor) {
77  const size_t M = 4;
78 
79  const Vector measured = Vector::Zero(M);
80 
81  auto model = Isotropic::Sigma(M, 1.0);
82  VectorEvaluationFactor<Chebyshev2> factor(key, measured, model, M, N, 0);
83 
85  graph.add(factor);
86 
87  gtsam::Matrix stateMatrix = gtsam::Matrix::Zero(M, N);
88 
90  initial.insert<gtsam::Matrix>(key, stateMatrix);
91 
93  parameters.setMaxIterations(20);
94  Values result =
96 
98 }
99 
100 //******************************************************************************
101 TEST(BasisFactors, Print) {
103  const size_t M = 1;
104 
105  const Vector measured = Vector::Ones(M) * 42;
106 
107  auto model = Isotropic::Sigma(M, 1.0);
108  VectorEvaluationFactor<Chebyshev2> factor(key, measured, model, M, N, 0);
109 
110  std::string expected =
111  " keys = { X0 }\n"
112  " noise model: unit (1) \n"
113  "FunctorizedFactor(X0)\n"
114  " measurement: [\n"
115  " 42\n"
116  "]\n"
117  " noise model sigmas: 1\n";
118 
120 }
121 
122 //******************************************************************************
123 TEST(BasisFactors, VectorComponentFactor) {
125  const int P = 4;
126  const size_t i = 2;
127  const double measured = 0.0, t = 3.0, a = 2.0, b = 4.0;
128  auto model = Isotropic::Sigma(1, 1.0);
129  VectorComponentFactor<Chebyshev2> factor(key, measured, model, P, N, i, t, a,
130  b);
131 
133  graph.add(factor);
134 
135  gtsam::Matrix stateMatrix = gtsam::Matrix::Zero(P, N);
136 
137  Values initial;
138  initial.insert<gtsam::Matrix>(key, stateMatrix);
139 
141  parameters.setMaxIterations(20);
142  Values result =
144 
146 }
147 
148 //******************************************************************************
149 TEST(BasisFactors, ManifoldEvaluationFactor) {
151  const Pose2 measured;
152  const double t = 3.0, a = 2.0, b = 4.0;
153  auto model = Isotropic::Sigma(3, 1.0);
154  ManifoldEvaluationFactor<Chebyshev2, Pose2> factor(key, measured, model, N, t,
155  a, b);
156 
158  graph.add(factor);
159 
160  gtsam::Matrix stateMatrix = gtsam::Matrix::Zero(3, N);
161 
162  Values initial;
163  initial.insert<gtsam::Matrix>(key, stateMatrix);
164 
166  parameters.setMaxIterations(20);
167  Values result =
169 
171  // Check Jacobians
173 }
174 
175 //******************************************************************************
176 TEST(BasisFactors, VecDerivativePrior) {
178  const size_t M = 4;
179 
180  const Vector measured = Vector::Zero(M);
181  auto model = Isotropic::Sigma(M, 1.0);
182  VectorDerivativeFactor<Chebyshev2> vecDPrior(key, measured, model, M, N, 0);
183 
185  graph.add(vecDPrior);
186 
187  gtsam::Matrix stateMatrix = gtsam::Matrix::Zero(M, N);
188 
189  Values initial;
190  initial.insert<gtsam::Matrix>(key, stateMatrix);
191 
193  parameters.setMaxIterations(20);
194  Values result =
196 
198 }
199 
200 //******************************************************************************
201 TEST(BasisFactors, ComponentDerivativeFactor) {
203  const size_t M = 4;
204 
205  double measured = 0;
206  auto model = Isotropic::Sigma(1, 1.0);
207  ComponentDerivativeFactor<Chebyshev2> controlDPrior(key, measured, model, M,
208  N, 0, 0);
209 
211  graph.add(controlDPrior);
212 
213  Values initial;
214  gtsam::Matrix stateMatrix = gtsam::Matrix::Zero(M, N);
215  initial.insert<gtsam::Matrix>(key, stateMatrix);
216 
218  parameters.setMaxIterations(20);
219  Values result =
221 
223 }
224 
225 /* ************************************************************************* */
226 int main() {
227  TestResult tr;
228  return TestRegistry::runAllTests(tr);
229 }
230 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
Chebyshev2.h
Pseudo-spectral parameterization for Chebyshev polynomials of the second kind.
Pose2.h
2D Pose
main
int main()
Definition: testBasisFactors.cpp:226
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
EXPECT_CORRECT_FACTOR_JACOBIANS
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
Definition: factorTesting.h:114
Vector.h
typedef and functions to augment Eigen's VectorXd
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Testable.h
Concept check for values that can be used in unit tests.
gtsam::ManifoldEvaluationFactor
Definition: BasisFactors.h:227
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
b
Scalar * b
Definition: benchVecAdd.cpp:17
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
initial
Values initial
Definition: OdometryOptimize.cpp:2
gtsam::assert_print_equal
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
Definition: TestableAssertions.h:352
gtsam::EvaluationFactor
Factor for enforcing the scalar value of the polynomial BASIS representation at x is the same as the ...
Definition: BasisFactors.h:39
measured
Point2 measured(-17, 30)
gtsam::VectorEvaluationFactor
Definition: BasisFactors.h:94
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
result
Values result
Definition: OdometryOptimize.cpp:8
TestableAssertions.h
Provides additional testing facilities for common data structures.
pruning_fixture::factor
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
gtsam::VectorComponentFactor
Definition: BasisFactors.h:158
gtsam::Chebyshev2
Definition: Chebyshev2.h:46
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
gtsam::NonlinearOptimizerParams
Definition: NonlinearOptimizerParams.h:35
gtsam::noiseModel::Isotropic
Definition: NoiseModel.h:541
parameters
static ConjugateGradientParameters parameters
Definition: testIterative.cpp:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
Basis.h
Compute an interpolating basis.
N
constexpr size_t N
Definition: testBasisFactors.cpp:43
factorTesting.h
Evaluate derivatives of a nonlinear factor numerically.
BasisFactors.h
Factor definitions for various Basis functors.
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
Symbol.h
TEST
TEST(BasisFactors, EvaluationFactor)
Definition: testBasisFactors.cpp:49
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
TestResult
Definition: TestResult.h:26
key
const gtsam::Symbol key('X', 0)
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
Values
std::vector< float > Values
Definition: sparse_setter.cpp:45
gtsam::Values
Definition: Values.h:65
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
P
static double P[]
Definition: ellpe.c:68
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::VectorDerivativeFactor
Definition: BasisFactors.h:326
initial
Definition: testScenarioRunner.cpp:148
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
FunctorizedFactor.h
align_3::t
Point2 t(10, 10)
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::ComponentDerivativeFactor
Definition: BasisFactors.h:379
gtsam::Pose2
Definition: Pose2.h:39
gtsam::Symbol
Definition: inference/Symbol.h:37
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:16:06