34 using namespace gtsam;
50 list<Key> actual = predecessorMap2Keys<Key>(p_map);
53 list<Key>::const_iterator it1 =
expected.begin();
54 list<Key>::const_iterator it2 = actual.begin();
55 for(; it1!=
expected.end(); it1++, it2++)
65 map<Key, SVertex> key2vertex;
71 std::tie(graph, root, key2vertex) = predecessorMap2Graph<SGraph<Key>, SVertex,
Key>(p_map);
74 CHECK(root == key2vertex[2]);
82 Pose2 p1(1.0, 2.0, 0.3),
p2(4.0, 5.0, 0.6),
p3(7.0, 8.0, 0.9),
p4(2.0, 2.0, 2.9);
96 std::shared_ptr<Values> actual = composePoses<NonlinearFactorGraph, BetweenFactor<Pose2>,
Pose2,
Key> (
graph, tree, rootPose);
99 expected.insert(1,
p1);
100 expected.insert(2,
p2);
101 expected.insert(3,
p3);
102 expected.insert(4, p4);
115 using namespace symbol_shorthand;
std::shared_ptr< Values > composePoses(const G &graph, const PredecessorMap< KEY > &tree, const POSE &rootPose)
void insert(const KEY &key, const KEY &parent)
PredecessorMap< KEY > findMinimumSpanningTree(const G &fg)
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
NonlinearFactorGraph graph
void g(const string &key, int i)
std::tuple< G, V, std::map< KEY, V > > predecessorMap2Graph(const PredecessorMap< KEY > &p_map)
Linear Factor Graph where all factors are Gaussians.
#define LONGS_EQUAL(expected, actual)
noiseModel::Diagonal::shared_ptr SharedDiagonal
Graph algorithm using boost library.
boost::graph_traits< SGraph< KEY > >::vertex_descriptor Vertex
#define EXPECT_LONGS_EQUAL(expected, actual)
Class between(const Class &g) const
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
TEST(Ordering, predecessorMap2Keys)
std::list< KEY > predecessorMap2Keys(const PredecessorMap< KEY > &p_map)