17 using namespace gtsam;
41 double range11 =
std::sqrt(4.0 + 4.0), range21 = 2.0, range32 = 2.0;
70 auto marginalCluster = boost::shared_ptr<Cluster>(
new Cluster(variableIndex, {
x1}, &
graph));
71 auto landmarkCluster = boost::shared_ptr<Cluster>(
new Cluster(variableIndex, {
l1,
l2}, &
graph));
72 auto rootCluster = boost::shared_ptr<Cluster>(
new Cluster(variableIndex, {
x2,
x3}, &
graph));
83 auto gfg = marginalCluster->linearize(initial);
88 ordering.push_back(
x1);
89 auto expected = gfg->eliminatePartialSequential(ordering);
92 throw std::runtime_error(
"Expected HessianFactor");
95 auto actual = marginalCluster->linearizeAndEliminate(initial);
109 auto marginalCluster = boost::shared_ptr<Cluster>(
new Cluster(variableIndex, {
x1}, &
graph));
110 auto landmarkCluster = boost::shared_ptr<Cluster>(
new Cluster(variableIndex, {
l1,
l2}, &
graph));
111 auto rootCluster = boost::shared_ptr<Cluster>(
new Cluster(variableIndex, {
x2,
x3}, &
graph));
115 clusterTree.
addRoot(rootCluster);
116 rootCluster->addChild(landmarkCluster);
117 landmarkCluster->addChild(marginalCluster);
143 for (
size_t i = 0;
i < 4;
i++)
static const Symbol l1('l', 1)
noiseModel::Diagonal::shared_ptr odometryNoise
static const Symbol l2('l', 2)
static int runAllTests(TestResult &result)
Point2 prior(const Point2 &x)
Prior on a single pose.
void insert(Key j, const Value &val)
static enum @843 ordering
static const Symbol x2('x', 2)
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Values updateCholesky(const Values &values)
NonlinearFactorGraph graph
static Rot2 fromDegrees(double theta)
Named constructor from angle in degrees.
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static NonlinearClusterTree Construct()
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
const sharedFactor at(size_t i) const
#define EXPECT_LONGS_EQUAL(expected, actual)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
static const Symbol x1('x', 1)
TEST(LPInitSolver, InfiniteLoopSingleVar)
A Gaussian factor using the canonical parameters (information form)
noiseModel::Diagonal::shared_ptr priorNoise
Pose2 odometry(2.0, 0.0, 0.0)
static const Symbol x3('x', 3)
void addRoot(const boost::shared_ptr< Cluster > &cluster)
NonlinearFactorGraph planarSLAMGraph()
Values planarSLAMValues()