Go to the documentation of this file.
32 using namespace gtsam;
66 Matrix expected_information = -originalHessian->information();
67 Matrix actual_information = antiHessian->information();
70 Vector expected_linear = -originalHessian->linearTerm();
71 Vector actual_linear = antiHessian->linearTerm();
74 double expected_f = -originalHessian->constantTerm();
75 double actual_f = antiHessian->constantTerm();
108 VectorValues expectedDeltas = expectedBayesNet->optimize();
static int runAllTests(TestResult &result)
Class between(const Class &g) const
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Linear Factor Graph where all factors are Gaussians.
A Gaussian factor using the canonical parameters (information form)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< AntiFactor > shared_ptr
#define EXPECT(condition)
Base class and parameters for nonlinear optimization algorithms.
double f2(const Vector2 &x)
Contains the HessianFactor class, a general quadratic factor.
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
std::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Variable ordering for the elimination algorithm.
Chordal Bayes Net, the result of eliminating a factor graph.
Ordering orderingCOLAMD() const
static const double sigma
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
std::shared_ptr< BetweenFactor > shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
void insert(Key j, const Vector &value)
noiseModel::Base::shared_ptr SharedNoiseModel
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
static enum @1096 ordering
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Factor Graph consisting of non-linear factors.
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
TEST(AntiFactor, NegativeHessian)
NonlinearFactorGraph graph
std::shared_ptr< This > shared_ptr
A non-templated config holding any types of Manifold-group elements.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:11