32 using namespace gtsam;
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();
97 values.insert(1, pose1);
98 values.insert(2, pose2);
108 VectorValues expectedDeltas = expectedBayesNet->optimize();
boost::shared_ptr< GaussianFactor > linearize(const Values &x) const override
TEST(AntiFactor, NegativeHessian)
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
static enum @843 ordering
static const double sigma
boost::shared_ptr< This > shared_ptr
double f2(const Vector2 &x)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
Ordering orderingCOLAMD() const
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
boost::shared_ptr< BetweenFactor > shared_ptr
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
#define EXPECT(condition)
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
boost::shared_ptr< AntiFactor > shared_ptr
Matrix information() const override
Contains the HessianFactor class, a general quadratic factor.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
Class between(const Class &g) const
A Gaussian factor using the canonical parameters (information form)
boost::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
Chordal Bayes Net, the result of eliminating a factor graph.
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Base class and parameters for nonlinear optimization algorithms.
noiseModel::Base::shared_ptr SharedNoiseModel