Go to the documentation of this file.
43 constexpr
size_t N = 2;
49 TEST(BasisFactors, EvaluationFactor) {
54 auto model = Isotropic::Sigma(1, 1.0);
61 functionValues.setZero();
75 TEST(BasisFactors, VectorEvaluationFactor) {
81 auto model = Isotropic::Sigma(
M, 1.0);
107 auto model = Isotropic::Sigma(
M, 1.0);
112 " noise model: unit (1) \n"
113 "FunctorizedFactor(X0)\n"
117 " noise model sigmas: 1\n";
123 TEST(BasisFactors, VectorComponentFactor) {
127 const double measured = 0.0,
t = 3.0,
a = 2.0,
b = 4.0;
128 auto model = Isotropic::Sigma(1, 1.0);
149 TEST(BasisFactors, ManifoldEvaluationFactor) {
152 const double t = 3.0,
a = 2.0,
b = 4.0;
153 auto model = Isotropic::Sigma(3, 1.0);
176 TEST(BasisFactors, VecDerivativePrior) {
181 auto model = Isotropic::Sigma(
M, 1.0);
201 TEST(BasisFactors, ComponentDerivativeFactor) {
206 auto model = Isotropic::Sigma(1, 1.0);
static int runAllTests(TestResult &result)
Pseudo-spectral parameterization for Chebyshev polynomials of the second kind.
virtual const Values & optimize()
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
typedef and functions to augment Eigen's VectorXd
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Concept check for values that can be used in unit tests.
#define EXPECT(condition)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
Factor for enforcing the scalar value of the polynomial BASIS representation at x is the same as the ...
Provides additional testing facilities for common data structures.
double error(const Values &values) const
static ConjugateGradientParameters parameters
Compute an interpolating basis.
Evaluate derivatives of a nonlinear factor numerically.
Factor definitions for various Basis functors.
TEST(BasisFactors, EvaluationFactor)
noiseModel::Diagonal::shared_ptr model
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
const gtsam::Symbol key('X', 0)
std::vector< float > Values
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Matrix< RealScalar, Dynamic, Dynamic > M
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:14