23 using namespace gtsam;
28 TEST(testNonlinearISAM, markov_chain ) {
29 int reorder_interval = 2;
43 init.insert(0, cur_pose);
44 expected.
insert(0, cur_pose);
45 isamChol.
update(start_factors, init);
46 isamQR.
update(start_factors, init);
51 for (
size_t i=1;
i<=nrPoses; ++
i) {
58 expected.
insert(i, cur_pose);
59 isamChol.
update(new_factors, new_init);
60 isamQR.
update(new_factors, new_init);
65 for (
size_t i=0;
i<nrPoses; ++
i) {
69 for (
size_t i=0;
i<nrPoses; ++
i) {
75 TEST(testNonlinearISAM, markov_chain_with_disconnects ) {
76 int reorder_interval = 2;
91 init.insert(0, cur_pose);
92 expected.
insert(0, cur_pose);
93 isamChol.
update(start_factors, init);
94 isamQR.
update(start_factors, init);
99 Key lm1 = nrPoses+1, lm2 = nrPoses+2, lm3 = nrPoses+3;
103 expected.
insert(lm3, landmark3);
107 for (
size_t i=1;
i<=nrPoses; ++
i) {
112 cur_pose = cur_pose.
compose(z);
114 expected.
insert(i, cur_pose);
120 new_factors.
addPrior(lm3, landmark3, model2);
123 new_init.insert(lm1,
Point2(0,0));
124 new_init.insert(lm2,
Point2(0,0));
125 new_init.insert(lm3,
Point2(0,0));
128 isamChol.
update(new_factors, new_init);
129 isamQR.
update(new_factors, new_init);
134 for (
size_t i=0;
i<nrPoses; ++
i)
138 for (
size_t i=0;
i<nrPoses; ++
i)
152 TEST(testNonlinearISAM, markov_chain_with_reconnect ) {
153 int reorder_interval = 2;
168 init.insert(0, cur_pose);
169 expected.
insert(0, cur_pose);
170 isamChol.
update(start_factors, init);
171 isamQR.
update(start_factors, init);
176 Key lm1 = nrPoses+1, lm2 = nrPoses+2, lm3 = nrPoses+3;
180 expected.
insert(lm3, landmark3);
184 for (
size_t i=1;
i<=nrPoses; ++
i) {
189 cur_pose = cur_pose.
compose(z);
191 expected.
insert(i, cur_pose);
197 new_factors.
addPrior(lm3, landmark3, model2);
200 new_init.insert(lm1,
Point2(0,0));
201 new_init.insert(lm2,
Point2(0,0));
202 new_init.insert(lm3,
Point2(0,0));
211 isamChol.
update(new_factors, new_init);
212 isamQR.
update(new_factors, new_init);
217 for (
size_t i=0;
i<nrPoses; ++
i)
221 for (
size_t i=0;
i<nrPoses; ++
i)
235 TEST(testNonlinearISAM, loop_closures ) {
243 vector<string>
lines;
244 lines.emplace_back(
"VERTEX2 0 0.000000 0.000000 0.000000");
245 lines.emplace_back(
"EDGE2 1 0 1.030390 0.011350 -0.012958");
246 lines.emplace_back(
"VERTEX2 1 1.030390 0.011350 -0.012958");
247 lines.emplace_back(
"EDGE2 2 1 1.013900 -0.058639 -0.013225");
248 lines.emplace_back(
"VERTEX2 2 2.043445 -0.060422 -0.026183");
249 lines.emplace_back(
"EDGE2 3 2 1.027650 -0.007456 0.004833");
250 lines.emplace_back(
"VERTEX2 3 3.070548 -0.094779 -0.021350");
251 lines.emplace_back(
"EDGE2 4 3 -0.012016 1.004360 1.566790");
252 lines.emplace_back(
"VERTEX2 4 3.079976 0.909609 1.545440");
253 lines.emplace_back(
"EDGE2 5 4 1.016030 0.014565 -0.016304");
254 lines.emplace_back(
"VERTEX2 5 3.091176 1.925681 1.529136");
255 lines.emplace_back(
"EDGE2 6 5 1.023890 0.006808 0.010981");
256 lines.emplace_back(
"VERTEX2 6 3.127018 2.948966 1.540117");
257 lines.emplace_back(
"EDGE2 7 6 0.957734 0.003159 0.010901");
258 lines.emplace_back(
"VERTEX2 7 3.153237 3.906347 1.551018");
259 lines.emplace_back(
"EDGE2 8 7 -1.023820 -0.013668 -3.093240");
260 lines.emplace_back(
"VERTEX2 8 3.146655 2.882457 -1.542222");
261 lines.emplace_back(
"EDGE2 9 8 1.023440 0.013984 -0.007802");
262 lines.emplace_back(
"EDGE2 9 5 0.033943 0.032439 -3.127400");
263 lines.emplace_back(
"VERTEX2 9 3.189873 1.859834 -1.550024");
264 lines.emplace_back(
"EDGE2 10 9 1.003350 0.022250 0.023491");
265 lines.emplace_back(
"EDGE2 10 3 0.044020 0.988477 -1.563530");
266 lines.emplace_back(
"VERTEX2 10 3.232959 0.857162 -1.526533");
267 lines.emplace_back(
"EDGE2 11 10 0.977245 0.019042 -0.028623");
268 lines.emplace_back(
"VERTEX2 11 3.295225 -0.118283 -1.555156");
269 lines.emplace_back(
"EDGE2 12 11 -0.996880 -0.025512 -3.126915");
270 lines.emplace_back(
"VERTEX2 12 3.254125 0.878076 1.601114");
271 lines.emplace_back(
"EDGE2 13 12 0.990646 0.018396 -0.016519");
272 lines.emplace_back(
"VERTEX2 13 3.205708 1.867709 1.584594");
273 lines.emplace_back(
"EDGE2 14 13 0.945873 0.008893 -0.002602");
274 lines.emplace_back(
"EDGE2 14 8 0.015808 0.021059 3.128310");
275 lines.emplace_back(
"VERTEX2 14 3.183765 2.813370 1.581993");
276 lines.emplace_back(
"EDGE2 15 14 1.000010 0.006428 0.028234");
277 lines.emplace_back(
"EDGE2 15 7 -0.014728 -0.001595 -0.019579");
278 lines.emplace_back(
"VERTEX2 15 3.166141 3.813245 1.610227");
280 auto model = noiseModel::Diagonal::Sigmas(
Vector3(3.0, 3.0, 0.5));
283 for (
const string&
str : lines) {
286 istringstream is(
str);
293 Key id = indexedPose->first;
294 initialEstimate.
insert(
Symbol(
'x',
id), indexedPose->second);
297 noiseModel::Diagonal::Sigmas(
Vector3(0.001, 0.001, 0.001));
300 isam.
update(graph, initialEstimate);
304 initialEstimate.
clear();
309 const auto betweenPose =
parseEdge(is, tag);
312 tie(id1, id2) = betweenPose->first;
Vector sample() const
sample from distribution
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
TEST(testNonlinearISAM, markov_chain)
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
std::pair< std::shared_ptr< GaussianConditional >, std::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
GTSAM_EXPORT Rot2 bearing(const Point2 &point, OptionalJacobian< 1, 3 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
void update(const NonlinearFactorGraph &newFactors, const Values &initialValues)
GTSAM_EXPORT double range(const Point2 &point, OptionalJacobian< 1, 3 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
NonlinearFactorGraph graph
Point2 landmark1(5.0, 1.5)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Point2 landmark2(7.0, 1.5)
std::optional< IndexedEdge > parseEdge(std::istream &is, const std::string &tag)
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const SharedNoiseModel model3
NonlinearISAM isam(relinearizeInterval)
sampling from a NoiseModel
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Class compose(const Class &g) const
noiseModel::Diagonal::shared_ptr SharedDiagonal
virtual void resize(size_t size)
#define EXPECT_LONGS_EQUAL(expected, actual)
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
void insert(Key j, const Value &val)
std::shared_ptr< Diagonal > shared_ptr
std::optional< IndexedPose > parseVertexPose(std::istream &is, const std::string &tag)
utility functions for loading datasets
std::uint64_t Key
Integer nonlinear key type.