Using initializers for almost everything in gtsam now.

release/4.3a0
Frank Dellaert 2023-01-07 20:11:34 -08:00
parent 8527b394ab
commit 7e4b033ece
17 changed files with 117 additions and 146 deletions

View File

@ -250,8 +250,7 @@ TEST(AdaptAutoDiff, SnavelyExpression) {
internal::upAligned(RecordSize) + P.traceSize() + X.traceSize(),
expression.traceSize());
set<Key> expected = list_of(1)(2);
const set<Key> expected{1, 2};
EXPECT(expected == expression.keys());
}

View File

@ -86,7 +86,7 @@ Vector f3(const Point3& p, OptionalJacobian<Eigen::Dynamic, 3> H) {
return p;
}
Point3_ pointExpression(1);
set<Key> expected = list_of(1);
const set<Key> expected{1};
} // namespace unary
// Create a unary expression that takes another expression as a single argument.
@ -186,14 +186,14 @@ TEST(Expression, BinaryToDouble) {
/* ************************************************************************* */
// Check keys of an expression created from class method.
TEST(Expression, BinaryKeys) {
set<Key> expected = list_of(1)(2);
const set<Key> expected{1, 2};
EXPECT(expected == binary::p_cam.keys());
}
/* ************************************************************************* */
// Check dimensions by calling `dims` method.
TEST(Expression, BinaryDimensions) {
map<Key, int> actual, expected = map_list_of<Key, int>(1, 6)(2, 3);
map<Key, int> actual, expected{{1, 6}, {2, 3}};
binary::p_cam.dims(actual);
EXPECT(actual == expected);
}
@ -223,14 +223,14 @@ Expression<Point2> uv_hat(uncalibrate<Cal3_S2>, K, projection);
/* ************************************************************************* */
// keys
TEST(Expression, TreeKeys) {
set<Key> expected = list_of(1)(2)(3);
const set<Key> expected{1, 2, 3};
EXPECT(expected == tree::uv_hat.keys());
}
/* ************************************************************************* */
// dimensions
TEST(Expression, TreeDimensions) {
map<Key, int> actual, expected = map_list_of<Key, int>(1, 6)(2, 3)(3, 5);
map<Key, int> actual, expected{{1, 6}, {2, 3}, {3, 5}};
tree::uv_hat.dims(actual);
EXPECT(actual == expected);
}
@ -261,7 +261,7 @@ TEST(Expression, compose1) {
Rot3_ R3 = R1 * R2;
// Check keys
set<Key> expected = list_of(1)(2);
const set<Key> expected{1, 2};
EXPECT(expected == R3.keys());
}
@ -273,7 +273,7 @@ TEST(Expression, compose2) {
Rot3_ R3 = R1 * R2;
// Check keys
set<Key> expected = list_of(1);
const set<Key> expected{1};
EXPECT(expected == R3.keys());
}
@ -285,7 +285,7 @@ TEST(Expression, compose3) {
Rot3_ R3 = R1 * R2;
// Check keys
set<Key> expected = list_of(3);
const set<Key> expected{3};
EXPECT(expected == R3.keys());
}
@ -298,7 +298,7 @@ TEST(Expression, compose4) {
Double_ R3 = R1 * R2;
// Check keys
set<Key> expected = list_of(1);
const set<Key> expected{1};
EXPECT(expected == R3.keys());
}
@ -322,7 +322,7 @@ TEST(Expression, ternary) {
Rot3_ ABC(composeThree, A, B, C);
// Check keys
set<Key> expected = list_of(1)(2)(3);
const set<Key> expected {1, 2, 3};
EXPECT(expected == ABC.keys());
}
@ -332,10 +332,10 @@ TEST(Expression, ScalarMultiply) {
const Key key(67);
const Point3_ expr = 23 * Point3_(key);
set<Key> expected_keys = list_of(key);
const set<Key> expected_keys{key};
EXPECT(expected_keys == expr.keys());
map<Key, int> actual_dims, expected_dims = map_list_of<Key, int>(key, 3);
map<Key, int> actual_dims, expected_dims {{key, 3}};
expr.dims(actual_dims);
EXPECT(actual_dims == expected_dims);
@ -363,10 +363,10 @@ TEST(Expression, BinarySum) {
const Key key(67);
const Point3_ sum_ = Point3_(key) + Point3_(Point3(1, 1, 1));
set<Key> expected_keys = list_of(key);
const set<Key> expected_keys{key};
EXPECT(expected_keys == sum_.keys());
map<Key, int> actual_dims, expected_dims = map_list_of<Key, int>(key, 3);
map<Key, int> actual_dims, expected_dims {{key, 3}};
sum_.dims(actual_dims);
EXPECT(actual_dims == expected_dims);
@ -458,7 +458,7 @@ TEST(Expression, UnaryOfSum) {
const Point3_ sum_ = Point3_(key1) + Point3_(key2);
const Double_ norm_(&gtsam::norm3, sum_);
map<Key, int> actual_dims, expected_dims = map_list_of<Key, int>(key1, 3)(key2, 3);
map<Key, int> actual_dims, expected_dims = {{key1, 3}, {key2, 3}};
norm_.dims(actual_dims);
EXPECT(actual_dims == expected_dims);
@ -481,7 +481,7 @@ TEST(Expression, WeightedSum) {
const Key key1(42), key2(67);
const Point3_ weighted_sum_ = 17 * Point3_(key1) + 23 * Point3_(key2);
map<Key, int> actual_dims, expected_dims = map_list_of<Key, int>(key1, 3)(key2, 3);
map<Key, int> actual_dims, expected_dims {{key1, 3}, {key2, 3}};
weighted_sum_.dims(actual_dims);
EXPECT(actual_dims == expected_dims);

View File

@ -220,9 +220,8 @@ TEST(Values, retract_full)
config0.insert(key1, Vector3(1.0, 2.0, 3.0));
config0.insert(key2, Vector3(5.0, 6.0, 7.0));
VectorValues delta = pair_list_of<Key, Vector>
(key1, Vector3(1.0, 1.1, 1.2))
(key2, Vector3(1.3, 1.4, 1.5));
VectorValues delta {{key1, Vector3(1.0, 1.1, 1.2)},
{key2, Vector3(1.3, 1.4, 1.5)}};
Values expected;
expected.insert(key1, Vector3(2.0, 3.1, 4.2));
@ -239,8 +238,7 @@ TEST(Values, retract_partial)
config0.insert(key1, Vector3(1.0, 2.0, 3.0));
config0.insert(key2, Vector3(5.0, 6.0, 7.0));
VectorValues delta = pair_list_of<Key, Vector>
(key2, Vector3(1.3, 1.4, 1.5));
VectorValues delta {{key2, Vector3(1.3, 1.4, 1.5)}};
Values expected;
expected.insert(key1, Vector3(1.0, 2.0, 3.0));
@ -275,9 +273,8 @@ TEST(Values, localCoordinates)
valuesA.insert(key1, Vector3(1.0, 2.0, 3.0));
valuesA.insert(key2, Vector3(5.0, 6.0, 7.0));
VectorValues expDelta = pair_list_of<Key, Vector>
(key1, Vector3(0.1, 0.2, 0.3))
(key2, Vector3(0.4, 0.5, 0.6));
VectorValues expDelta{{key1, Vector3(0.1, 0.2, 0.3)},
{key2, Vector3(0.4, 0.5, 0.6)}};
Values valuesB = valuesA.retract(expDelta);

View File

@ -454,8 +454,8 @@ TEST(GeneralSFMFactor, BinaryJacobianFactor) {
using namespace noiseModel;
Rot2 R = Rot2::fromAngle(0.3);
Matrix2 cov = R.matrix() * R.matrix().transpose();
models += SharedNoiseModel(), Unit::Create(2), //
Isotropic::Sigma(2, 0.5), Constrained::All(2), Gaussian::Covariance(cov);
models = {SharedNoiseModel(), Unit::Create(2), Isotropic::Sigma(2, 0.5),
Constrained::All(2), Gaussian::Covariance(cov)};
}
// Now loop over all these noise models

View File

@ -65,17 +65,15 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) {
Matrix3 P = (E.transpose() * E).inverse();
double alpha = 0.5;
VectorValues xvalues = map_list_of //
(0, Vector::Constant(6, 2))//
(1, Vector::Constant(6, 4))//
(2, Vector::Constant(6, 0))// distractor
(3, Vector::Constant(6, 8));
VectorValues xvalues{{0, Vector::Constant(6, 2)}, //
{1, Vector::Constant(6, 4)}, //
{2, Vector::Constant(6, 0)}, // distractor
{3, Vector::Constant(6, 8)}};
VectorValues yExpected = map_list_of//
(0, Vector::Constant(6, 27))//
(1, Vector::Constant(6, -40))//
(2, Vector::Constant(6, 0))// distractor
(3, Vector::Constant(6, 279));
VectorValues yExpected{{0, Vector::Constant(6, 27)}, //
{1, Vector::Constant(6, -40)}, //
{2, Vector::Constant(6, 0)}, // distractor
{3, Vector::Constant(6, 279)}};
// Create full F
size_t M=4, m = 3, d = 6;

View File

@ -26,38 +26,37 @@
#include <gtsam/symbolic/SymbolicBayesTree.h>
#include <gtsam/inference/Ordering.h>
#include <gtsam/inference/Symbol.h>
#include <boost/assign/list_of.hpp>
namespace gtsam {
namespace {
const SymbolicFactorGraph simpleTestGraph1 = boost::assign::list_of
(boost::make_shared<SymbolicFactor>(0,1))
(boost::make_shared<SymbolicFactor>(0,2))
(boost::make_shared<SymbolicFactor>(1,4))
(boost::make_shared<SymbolicFactor>(2,4))
(boost::make_shared<SymbolicFactor>(3,4));
const SymbolicFactorGraph simpleTestGraph1 {
boost::make_shared<SymbolicFactor>(0,1),
boost::make_shared<SymbolicFactor>(0,2),
boost::make_shared<SymbolicFactor>(1,4),
boost::make_shared<SymbolicFactor>(2,4),
boost::make_shared<SymbolicFactor>(3,4)};
const SymbolicBayesNet simpleTestGraph1BayesNet = boost::assign::list_of
(boost::make_shared<SymbolicConditional>(0,1,2))
(boost::make_shared<SymbolicConditional>(1,2,4))
(boost::make_shared<SymbolicConditional>(2,4))
(boost::make_shared<SymbolicConditional>(3,4))
(boost::make_shared<SymbolicConditional>(4));
const SymbolicBayesNet simpleTestGraph1BayesNet {
boost::make_shared<SymbolicConditional>(0,1,2),
boost::make_shared<SymbolicConditional>(1,2,4),
boost::make_shared<SymbolicConditional>(2,4),
boost::make_shared<SymbolicConditional>(3,4),
boost::make_shared<SymbolicConditional>(4)};
const SymbolicFactorGraph simpleTestGraph2 = boost::assign::list_of
(boost::make_shared<SymbolicFactor>(0,1))
(boost::make_shared<SymbolicFactor>(0,2))
(boost::make_shared<SymbolicFactor>(1,3))
(boost::make_shared<SymbolicFactor>(1,4))
(boost::make_shared<SymbolicFactor>(2,3))
(boost::make_shared<SymbolicFactor>(4,5));
const SymbolicFactorGraph simpleTestGraph2 {
boost::make_shared<SymbolicFactor>(0,1),
boost::make_shared<SymbolicFactor>(0,2),
boost::make_shared<SymbolicFactor>(1,3),
boost::make_shared<SymbolicFactor>(1,4),
boost::make_shared<SymbolicFactor>(2,3),
boost::make_shared<SymbolicFactor>(4,5)};
/** 1 - 0 - 2 - 3 */
const SymbolicFactorGraph simpleChain = boost::assign::list_of
(boost::make_shared<SymbolicFactor>(1,0))
(boost::make_shared<SymbolicFactor>(0,2))
(boost::make_shared<SymbolicFactor>(2,3));
const SymbolicFactorGraph simpleChain {
boost::make_shared<SymbolicFactor>(1,0),
boost::make_shared<SymbolicFactor>(0,2),
boost::make_shared<SymbolicFactor>(2,3)};
/* ************************************************************************* *
* 2 3
@ -67,10 +66,10 @@ namespace gtsam {
SymbolicBayesTree result;
result.insertRoot(boost::make_shared<SymbolicBayesTreeClique>(
boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(boost::assign::list_of(2)(3), 2))));
SymbolicConditional::FromKeys(KeyVector{2,3}, 2))));
result.addClique(boost::make_shared<SymbolicBayesTreeClique>(
boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(boost::assign::list_of(0)(1)(2), 2))),
SymbolicConditional::FromKeys(KeyVector{0,1,2}, 2))),
result.roots().front());
return result;
}
@ -84,39 +83,39 @@ namespace gtsam {
_L_=gtsam::symbol_shorthand::L(0), _B_=gtsam::symbol_shorthand::B(0);
// Factor graph for Asia example
const SymbolicFactorGraph asiaGraph = boost::assign::list_of
(boost::make_shared<SymbolicFactor>(_T_))
(boost::make_shared<SymbolicFactor>(_S_))
(boost::make_shared<SymbolicFactor>(_T_, _E_, _L_))
(boost::make_shared<SymbolicFactor>(_L_, _S_))
(boost::make_shared<SymbolicFactor>(_S_, _B_))
(boost::make_shared<SymbolicFactor>(_E_, _B_))
(boost::make_shared<SymbolicFactor>(_E_, _X_));
const SymbolicFactorGraph asiaGraph = {
boost::make_shared<SymbolicFactor>(_T_),
boost::make_shared<SymbolicFactor>(_S_),
boost::make_shared<SymbolicFactor>(_T_, _E_, _L_),
boost::make_shared<SymbolicFactor>(_L_, _S_),
boost::make_shared<SymbolicFactor>(_S_, _B_),
boost::make_shared<SymbolicFactor>(_E_, _B_),
boost::make_shared<SymbolicFactor>(_E_, _X_)};
const SymbolicBayesNet asiaBayesNet = boost::assign::list_of
(boost::make_shared<SymbolicConditional>(_T_, _E_, _L_))
(boost::make_shared<SymbolicConditional>(_X_, _E_))
(boost::make_shared<SymbolicConditional>(_E_, _B_, _L_))
(boost::make_shared<SymbolicConditional>(_S_, _B_, _L_))
(boost::make_shared<SymbolicConditional>(_L_, _B_))
(boost::make_shared<SymbolicConditional>(_B_));
const SymbolicBayesNet asiaBayesNet = {
boost::make_shared<SymbolicConditional>(_T_, _E_, _L_),
boost::make_shared<SymbolicConditional>(_X_, _E_),
boost::make_shared<SymbolicConditional>(_E_, _B_, _L_),
boost::make_shared<SymbolicConditional>(_S_, _B_, _L_),
boost::make_shared<SymbolicConditional>(_L_, _B_),
boost::make_shared<SymbolicConditional>(_B_)};
SymbolicBayesTree __asiaBayesTree() {
SymbolicBayesTree result;
result.insertRoot(boost::make_shared<SymbolicBayesTreeClique>(
boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(boost::assign::list_of(_E_)(_L_)(_B_), 3))));
SymbolicConditional::FromKeys(KeyVector{_E_, _L_, _B_}, 3))));
result.addClique(boost::make_shared<SymbolicBayesTreeClique>(
boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(boost::assign::list_of(_S_)(_B_) (_L_), 1))),
SymbolicConditional::FromKeys(KeyVector{_S_, _B_, _L_}, 1))),
result.roots().front());
result.addClique(boost::make_shared<SymbolicBayesTreeClique>(
boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(boost::assign::list_of(_T_)(_E_)(_L_), 1))),
SymbolicConditional::FromKeys(KeyVector{_T_, _E_, _L_}, 1))),
result.roots().front());
result.addClique(boost::make_shared<SymbolicBayesTreeClique>(
boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(boost::assign::list_of(_X_)(_E_), 1))),
SymbolicConditional::FromKeys(KeyVector{_X_, _E_}, 1))),
result.roots().front());
return result;
}
@ -124,7 +123,6 @@ namespace gtsam {
const SymbolicBayesTree asiaBayesTree = __asiaBayesTree();
/* ************************************************************************* */
const Ordering asiaOrdering = boost::assign::list_of(_X_)(_T_)(_S_)(_E_)(_L_)(_B_);
const Ordering asiaOrdering{_X_, _T_, _S_, _E_, _L_, _B_};
}
}

View File

@ -15,8 +15,6 @@
* @author Frank Dellaert
*/
#include <boost/assign/list_of.hpp>
using namespace boost::assign;
#include <boost/make_shared.hpp>
#include <CppUnitLite/TestHarness.h>
@ -69,8 +67,7 @@ TEST( SymbolicConditional, threeParents )
/* ************************************************************************* */
TEST( SymbolicConditional, fourParents )
{
SymbolicConditional c0 = SymbolicConditional::FromKeys(
list_of(0)(1)(2)(3)(4), 1);
auto c0 = SymbolicConditional::FromKeys(KeyVector{0, 1, 2, 3, 4}, 1);
LONGS_EQUAL(1, (long)c0.nrFrontals());
LONGS_EQUAL(4, (long)c0.nrParents());
}
@ -78,9 +75,8 @@ TEST( SymbolicConditional, fourParents )
/* ************************************************************************* */
TEST( SymbolicConditional, FromRange )
{
SymbolicConditional::shared_ptr c0 =
boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(list_of(1)(2)(3)(4)(5), 2));
auto c0 = boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(KeyVector{1, 2, 3, 4, 5}, 2));
LONGS_EQUAL(2, (long)c0->nrFrontals());
LONGS_EQUAL(3, (long)c0->nrParents());
}

View File

@ -21,8 +21,6 @@
#include <gtsam/symbolic/SymbolicConditional.h>
#include <gtsam/symbolic/SymbolicFactorGraph.h>
#include <boost/assign/std/vector.hpp>
#include <boost/assign/list_of.hpp>
#include <boost/make_shared.hpp>
#include <boost/tuple/tuple.hpp>
@ -70,19 +68,19 @@ TEST(SymbolicFactor, Constructors)
/* ************************************************************************* */
TEST(SymbolicFactor, EliminateSymbolic)
{
const SymbolicFactorGraph factors = list_of
(SymbolicFactor(2,4,6))
(SymbolicFactor(1,2,5))
(SymbolicFactor(0,3));
const SymbolicFactorGraph factors = {
boost::make_shared<SymbolicFactor>(2, 4, 6),
boost::make_shared<SymbolicFactor>(1, 2, 5),
boost::make_shared<SymbolicFactor>(0, 3)};
const SymbolicFactor expectedFactor(4,5,6);
const SymbolicConditional expectedConditional =
SymbolicConditional::FromKeys(list_of(0)(1)(2)(3)(4)(5)(6), 4);
SymbolicConditional::FromKeys(KeyVector{0,1,2,3,4,5,6}, 4);
SymbolicFactor::shared_ptr actualFactor;
SymbolicConditional::shared_ptr actualConditional;
boost::tie(actualConditional, actualFactor) =
EliminateSymbolic(factors, list_of(0)(1)(2)(3));
EliminateSymbolic(factors, Ordering{0, 1, 2, 3});
CHECK(assert_equal(expectedConditional, *actualConditional));
CHECK(assert_equal(expectedFactor, *actualFactor));

View File

@ -25,7 +25,8 @@
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/std/set.hpp>
#include <boost/assign/list_of.hpp>
using namespace boost::assign;
using namespace std;
using namespace gtsam;
@ -33,16 +34,14 @@ using namespace boost::assign;
/* ************************************************************************* */
TEST(SymbolicFactorGraph, keys1) {
KeySet expected;
expected += 0, 1, 2, 3, 4;
KeySet expected {0, 1, 2, 3, 4};
KeySet actual = simpleTestGraph1.keys();
EXPECT(expected == actual);
}
/* ************************************************************************* */
TEST(SymbolicFactorGraph, keys2) {
KeySet expected;
expected += 0, 1, 2, 3, 4, 5;
KeySet expected {0, 1, 2, 3, 4, 5};
KeySet actual = simpleTestGraph2.keys();
EXPECT(expected == actual);
}
@ -50,8 +49,7 @@ TEST(SymbolicFactorGraph, keys2) {
/* ************************************************************************* */
TEST(SymbolicFactorGraph, eliminateFullSequential) {
// Test with simpleTestGraph1
Ordering order;
order += 0, 1, 2, 3, 4;
Ordering order{0, 1, 2, 3, 4};
SymbolicBayesNet actual1 = *simpleTestGraph1.eliminateSequential(order);
EXPECT(assert_equal(simpleTestGraph1BayesNet, actual1));
@ -63,7 +61,7 @@ TEST(SymbolicFactorGraph, eliminateFullSequential) {
/* ************************************************************************* */
TEST(SymbolicFactorGraph, eliminatePartialSequential) {
// Eliminate 0 and 1
const Ordering order = list_of(0)(1);
const Ordering order {0, 1};
const SymbolicBayesNet expectedBayesNet =
list_of(SymbolicConditional(0, 1, 2))(SymbolicConditional(1, 2, 3, 4));
@ -74,7 +72,7 @@ TEST(SymbolicFactorGraph, eliminatePartialSequential) {
SymbolicBayesNet::shared_ptr actualBayesNet;
SymbolicFactorGraph::shared_ptr actualSfg;
boost::tie(actualBayesNet, actualSfg) =
simpleTestGraph2.eliminatePartialSequential(Ordering(list_of(0)(1)));
simpleTestGraph2.eliminatePartialSequential(Ordering{0, 1});
EXPECT(assert_equal(expectedSfg, *actualSfg));
EXPECT(assert_equal(expectedBayesNet, *actualBayesNet));
@ -82,8 +80,7 @@ TEST(SymbolicFactorGraph, eliminatePartialSequential) {
SymbolicBayesNet::shared_ptr actualBayesNet2;
SymbolicFactorGraph::shared_ptr actualSfg2;
boost::tie(actualBayesNet2, actualSfg2) =
simpleTestGraph2.eliminatePartialSequential(
list_of(0)(1).convert_to_container<KeyVector>());
simpleTestGraph2.eliminatePartialSequential(Ordering{0, 1});
EXPECT(assert_equal(expectedSfg, *actualSfg2));
EXPECT(assert_equal(expectedBayesNet, *actualBayesNet2));
@ -105,7 +102,7 @@ TEST(SymbolicFactorGraph, eliminatePartialMultifrontal) {
SymbolicBayesTree expectedBayesTree;
SymbolicConditional::shared_ptr root =
boost::make_shared<SymbolicConditional>(
SymbolicConditional::FromKeys(list_of(4)(5)(1), 2));
SymbolicConditional::FromKeys(KeyVector{4, 5, 1}, 2));
expectedBayesTree.insertRoot(
boost::make_shared<SymbolicBayesTreeClique>(root));
@ -116,7 +113,7 @@ TEST(SymbolicFactorGraph, eliminatePartialMultifrontal) {
SymbolicBayesTree::shared_ptr actualBayesTree;
SymbolicFactorGraph::shared_ptr actualFactorGraph;
boost::tie(actualBayesTree, actualFactorGraph) =
simpleTestGraph2.eliminatePartialMultifrontal(Ordering(list_of(4)(5)));
simpleTestGraph2.eliminatePartialMultifrontal(Ordering{4, 5});
EXPECT(assert_equal(expectedFactorGraph, *actualFactorGraph));
EXPECT(assert_equal(expectedBayesTree, *actualBayesTree));
@ -132,8 +129,7 @@ TEST(SymbolicFactorGraph, eliminatePartialMultifrontal) {
SymbolicBayesTree::shared_ptr actualBayesTree2;
SymbolicFactorGraph::shared_ptr actualFactorGraph2;
boost::tie(actualBayesTree2, actualFactorGraph2) =
simpleTestGraph2.eliminatePartialMultifrontal(
list_of<Key>(4)(5).convert_to_container<KeyVector>());
simpleTestGraph2.eliminatePartialMultifrontal(KeyVector{4, 5});
EXPECT(assert_equal(expectedFactorGraph, *actualFactorGraph2));
EXPECT(assert_equal(expectedBayesTree2, *actualBayesTree2));
@ -146,7 +142,7 @@ TEST(SymbolicFactorGraph, marginalMultifrontalBayesNet) {
SymbolicConditional(2, 3))(SymbolicConditional(3));
SymbolicBayesNet actual1 = *simpleTestGraph2.marginalMultifrontalBayesNet(
Ordering(list_of(0)(1)(2)(3)));
Ordering{0, 1, 2, 3});
EXPECT(assert_equal(expectedBayesNet, actual1));
}
@ -184,7 +180,7 @@ TEST(SymbolicFactorGraph, marginals) {
fg.push_factor(3, 4);
// eliminate
Ordering ord(list_of(3)(4)(2)(1)(0));
Ordering ord{3, 4, 2, 1, 0};
auto actual = fg.eliminateSequential(ord);
SymbolicBayesNet expected;
expected.emplace_shared<SymbolicConditional>(3, 4);
@ -196,7 +192,7 @@ TEST(SymbolicFactorGraph, marginals) {
{
// jointBayesNet
Ordering ord(list_of(0)(4)(3));
Ordering ord {0, 4, 3};
auto actual = fg.eliminatePartialSequential(ord);
SymbolicBayesNet expectedBN;
expectedBN.emplace_shared<SymbolicConditional>(0, 1, 2);
@ -207,7 +203,7 @@ TEST(SymbolicFactorGraph, marginals) {
{
// jointBayesNet
Ordering ord(list_of(0)(2)(3));
Ordering ord {0, 2, 3};
auto actual = fg.eliminatePartialSequential(ord);
SymbolicBayesNet expectedBN;
expectedBN.emplace_shared<SymbolicConditional>(0, 1, 2);
@ -218,7 +214,7 @@ TEST(SymbolicFactorGraph, marginals) {
{
// conditionalBayesNet
Ordering ord(list_of(0)(2));
Ordering ord{0, 2};
auto actual = fg.eliminatePartialSequential(ord);
SymbolicBayesNet expectedBN;
expectedBN.emplace_shared<SymbolicConditional>(0, 1, 2);
@ -306,7 +302,7 @@ TEST(SymbolicFactorGraph, add_factors) {
expected.push_factor(1);
expected.push_factor(11);
expected.push_factor(2);
const FactorIndices expectedIndices = list_of(1)(3);
const FactorIndices expectedIndices {1, 3};
const FactorIndices actualIndices = fg1.add_factors(fg2, true);
EXPECT(assert_equal(expected, fg1));
@ -314,7 +310,7 @@ TEST(SymbolicFactorGraph, add_factors) {
expected.push_factor(1);
expected.push_factor(2);
const FactorIndices expectedIndices2 = list_of(4)(5);
const FactorIndices expectedIndices2 {4, 5};
const FactorIndices actualIndices2 = fg1.add_factors(fg2, false);
EXPECT(assert_equal(expected, fg1));

View File

@ -20,9 +20,6 @@
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/std/list.hpp> // for operator +=
using namespace boost::assign;
using namespace std;
using namespace gtsam;
@ -86,7 +83,7 @@ TEST( SymbolicISAM, iSAM )
fullGraph += SymbolicFactor(_B_, _S_);
// This ordering is chosen to match the one chosen by COLAMD during the ISAM update
Ordering ordering(list_of(_X_)(_B_)(_S_)(_E_)(_L_)(_T_));
Ordering ordering {_X_, _B_, _S_, _E_, _L_, _T_};
SymbolicBayesTree expected = *fullGraph.eliminateMultifrontal(ordering);
// Add factor on B and S

View File

@ -23,9 +23,6 @@
#include <gtsam/symbolic/SymbolicEliminationTree.h>
#include <gtsam/symbolic/SymbolicJunctionTree.h>
#include <boost/assign/list_of.hpp>
using namespace boost::assign;
#include "symbolicExampleGraphs.h"
using namespace gtsam;
@ -43,9 +40,9 @@ TEST( JunctionTree, constructor )
SymbolicJunctionTree actual(SymbolicEliminationTree(simpleChain, order));
SymbolicJunctionTree::Node::Keys
frontal1 = list_of(2)(3),
frontal2 = list_of(0)(1),
sep1, sep2 = list_of(2);
frontal1 {2, 3},
frontal2 {0, 1},
sep1, sep2 {2};
EXPECT(assert_container_equality(frontal1, actual.roots().front()->orderedFrontalKeys));
//EXPECT(assert_equal(sep1, actual.roots().front()->separator));
LONGS_EQUAL(1, (long)actual.roots().front()->factors.size());

View File

@ -22,10 +22,6 @@
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/std/list.hpp>
#include <boost/assign/list_of.hpp>
using namespace boost::assign;
using namespace std;
using namespace gtsam;
@ -79,7 +75,7 @@ TEST(VariableIndex, augment2) {
VariableIndex expected(fgCombined);
FactorIndices newIndices = list_of(5)(6)(7)(8);
FactorIndices newIndices {5, 6, 7, 8};
VariableIndex actual(fg1);
actual.augment(fg2, newIndices);
@ -108,7 +104,7 @@ TEST(VariableIndex, remove) {
vector<size_t> indices;
indices.push_back(0); indices.push_back(1); indices.push_back(2); indices.push_back(3);
actual.remove(indices.begin(), indices.end(), fg1);
std::list<Key> unusedVariables; unusedVariables += 0, 9;
std::list<Key> unusedVariables{0, 9};
actual.removeUnusedVariables(unusedVariables.begin(), unusedVariables.end());
CHECK(assert_equal(expected, actual));
@ -135,7 +131,7 @@ TEST(VariableIndex, deep_copy) {
vector<size_t> indices;
indices.push_back(0); indices.push_back(1); indices.push_back(2); indices.push_back(3);
clone.remove(indices.begin(), indices.end(), fg1);
std::list<Key> unusedVariables; unusedVariables += 0, 9;
std::list<Key> unusedVariables{0, 9};
clone.removeUnusedVariables(unusedVariables.begin(), unusedVariables.end());
// When modifying the clone, the original should have stayed the same

View File

@ -40,11 +40,10 @@ class GTSAM_UNSTABLE_EXPORT Constraint : public DiscreteFactor {
protected:
/// Construct unary constraint factor.
Constraint(Key j) : DiscreteFactor(boost::assign::cref_list_of<1>(j)) {}
Constraint(Key j) : DiscreteFactor(KeyVector{j}) {}
/// Construct binary constraint factor.
Constraint(Key j1, Key j2)
: DiscreteFactor(boost::assign::cref_list_of<2>(j1)(j2)) {}
Constraint(Key j1, Key j2) : DiscreteFactor(KeyVector{j1, j2}) {}
/// Construct n-way constraint factor.
Constraint(const KeyVector& js) : DiscreteFactor(js) {}

View File

@ -73,7 +73,7 @@ public:
const SharedGaussian& model_inlier, const SharedGaussian& model_outlier,
const double prior_inlier, const double prior_outlier,
const bool flag_bump_up_near_zero_probs = false) :
Base(cref_list_of<2>(key1)(key2)), key1_(key1), key2_(key2), measured_(
Base(KeyVector{key1, key2}), key1_(key1), key2_(key2), measured_(
measured), model_inlier_(model_inlier), model_outlier_(model_outlier), prior_inlier_(
prior_inlier), prior_outlier_(prior_outlier), flag_bump_up_near_zero_probs_(
flag_bump_up_near_zero_probs) {

View File

@ -15,7 +15,7 @@ namespace gtsam {
/* ************************************************************************* */
DummyFactor::DummyFactor(const Key& key1, size_t dim1, const Key& key2, size_t dim2)
: NonlinearFactor(cref_list_of<2>(key1)(key2))
: NonlinearFactor(KeyVector{key1, key2})
{
dims_.push_back(dim1);
dims_.push_back(dim2);

View File

@ -70,7 +70,7 @@ namespace gtsam {
TransformBtwRobotsUnaryFactor(Key key, const VALUE& measured, Key keyA, Key keyB,
const gtsam::Values& valA, const gtsam::Values& valB,
const SharedGaussian& model) :
Base(cref_list_of<1>(key)), key_(key), measured_(measured), keyA_(keyA), keyB_(keyB),
Base(KeyVector{key}), key_(key), measured_(measured), keyA_(keyA), keyB_(keyB),
model_(model){
setValAValB(valA, valB);

View File

@ -84,7 +84,7 @@ namespace gtsam {
const double prior_inlier, const double prior_outlier,
const bool flag_bump_up_near_zero_probs = false,
const bool start_with_M_step = false) :
Base(cref_list_of<1>(key)), key_(key), measured_(measured), keyA_(keyA), keyB_(keyB),
Base(KeyVector{key}), key_(key), measured_(measured), keyA_(keyA), keyB_(keyB),
model_inlier_(model_inlier), model_outlier_(model_outlier),
prior_inlier_(prior_inlier), prior_outlier_(prior_outlier), flag_bump_up_near_zero_probs_(flag_bump_up_near_zero_probs),
start_with_M_step_(false){