27 #include <boost/algorithm/string.hpp> 28 #include <boost/archive/text_iarchive.hpp> 29 #include <boost/archive/text_oarchive.hpp> 30 #include <boost/serialization/vector.hpp> 55 template <
typename Container>
56 static vector<size_t>
sort_idx(
const Container &src) {
57 typedef typename Container::value_type
T;
58 const size_t n = src.size();
59 vector<std::pair<size_t, T> > tmp;
61 for (
size_t i = 0;
i <
n;
i++) tmp.emplace_back(
i, src[
i]);
64 std::stable_sort(tmp.begin(), tmp.end());
69 for (
size_t i = 0; i <
n; i++) {
70 idx.push_back(tmp[i].
first);
77 edges_.reserve(indices.size());
78 for (
const size_t &index : indices) {
79 const Edge e{index, 1.0};
89 eid.push_back(edge.index);
96 std::ofstream
os(fn.c_str());
97 boost::archive::text_oarchive oa(
os);
104 std::ifstream is(fn.c_str());
105 boost::archive::text_iarchive ia(is);
115 os << edge.
index <<
"(" << std::setprecision(2) << edge.
weight <<
")";
123 os <<
"Subgraph" << endl;
124 for (
const auto &
e : subgraph.
edges()) {
135 os <<
"SubgraphBuilderParameters" << endl
136 <<
"skeleton: " << skeletonTranslator(skeletonType) << endl
137 <<
"skeleton weight: " << skeletonWeightTranslator(skeletonWeight)
139 <<
"augmentation weight: " 140 << augmentationWeightTranslator(augmentationWeight) << endl;
153 boost::algorithm::to_upper(s);
154 if (s ==
"NATURALCHAIN")
158 else if (s ==
"KRUSKAL")
160 throw std::invalid_argument(
161 "SubgraphBuilderParameters::skeletonTranslator undefined string " + s);
167 if (s == NATURALCHAIN)
168 return "NATURALCHAIN";
171 else if (s == KRUSKAL)
181 boost::algorithm::to_upper(s);
188 else if (s ==
"RANDOM")
190 throw std::invalid_argument(
191 "SubgraphBuilderParameters::skeletonWeightTranslator undefined string " +
201 else if (w == RHS_2NORM)
203 else if (w == LHS_FNORM)
205 else if (w == RANDOM)
214 const std::string &src) {
216 boost::algorithm::to_upper(s);
217 if (s ==
"SKELETON")
return SKELETON;
220 throw std::invalid_argument(
221 "SubgraphBuilder::Parameters::augmentationWeightTranslator undefined " 230 if (w == SKELETON)
return "SKELETON";
240 const vector<double> &weights)
const {
244 return natural_chain(gfg);
250 return kruskal(gfg, ordering, weights);
253 std::cerr <<
"SubgraphBuilder::buildTree undefined skeleton type" << endl;
256 return vector<size_t>();
261 vector<size_t> unaryFactorIndices;
263 for (
const auto &factor : gfg) {
264 if (factor->size() == 1) {
265 unaryFactorIndices.push_back(index);
269 return unaryFactorIndices;
275 vector<size_t> chainFactorIndices;
278 if (gf->size() == 2) {
279 const Key k0 = gf->keys()[0], k1 = gf->keys()[1];
280 if ((k1 - k0) == 1 || (k0 - k1) == 1) chainFactorIndices.push_back(index);
284 return chainFactorIndices;
293 const size_t n = variableIndex.
size();
296 vector<size_t> bfsFactorIndices;
297 bfsFactorIndices.reserve(n - 1);
300 std::queue<size_t>
q;
303 std::set<size_t> flags;
308 const size_t head = q.front();
310 for (
const size_t index : variableIndex[head]) {
312 for (
const size_t key : gf.
keys()) {
313 if (flags.count(
key) == 0) {
321 return bfsFactorIndices;
327 const vector<double> &weights)
const {
329 const size_t n = variableIndex.
size();
330 const vector<size_t> sortedIndices =
sort_idx(weights);
333 vector<size_t> treeIndices;
334 treeIndices.reserve(n - 1);
341 for (
const size_t index : sortedIndices) {
344 if (
keys.size() != 2)
continue;
345 const size_t u = ordering.find(
keys[0])->second,
346 v = ordering.find(
keys[1])->second;
349 treeIndices.push_back(index);
350 sum += weights[index];
351 if (++count == n - 1)
break;
359 const size_t t)
const {
360 std::mt19937
rng(42);
367 const auto &
p = parameters_;
370 const size_t n = inverse_ordering.size(),
m = gfg.
size();
375 size_t numExtraEdges = n *
p.augmentationFactor;
376 const size_t numRemaining =
m - (n - 1);
377 numExtraEdges =
std::min(numExtraEdges, numRemaining / 2);
380 vector<double> weights = this->weights(gfg);
383 const vector<size_t>
tree = buildTree(gfg, forward_ordering, weights);
384 if (tree.size() != n - 1) {
385 throw std::runtime_error(
386 "SubgraphBuilder::operator() failure: tree.size() != n-1, might be caused by disconnected graph");
390 for (
const size_t index : tree) {
391 weights[index] = 0.0;
395 vector<size_t> offTree = sample(weights, numExtraEdges);
397 vector<size_t> subgraph =
unary(gfg);
398 subgraph.insert(subgraph.end(), tree.begin(), tree.end());
399 subgraph.insert(subgraph.end(), offTree.begin(), offTree.end());
407 const size_t m = gfg.
size();
412 switch (parameters_.skeletonWeight) {
414 weight.push_back(1.0);
418 boost::dynamic_pointer_cast<JacobianFactor>(gf)) {
419 weight.push_back(jf->getb().norm());
421 boost::dynamic_pointer_cast<HessianFactor>(gf)) {
422 weight.push_back(hf->linearTerm().norm());
427 boost::dynamic_pointer_cast<JacobianFactor>(gf)) {
428 weight.push_back(
std::sqrt(jf->getA().squaredNorm()));
430 boost::dynamic_pointer_cast<HessianFactor>(gf)) {
431 weight.push_back(
std::sqrt(hf->information().squaredNorm()));
436 weight.push_back(std::rand() % 100 + 1.0);
440 throw std::invalid_argument(
441 "SubgraphBuilder::weights: undefined weight scheme ");
452 auto subgraphFactors = boost::make_shared<GaussianFactorGraph>();
453 subgraphFactors->reserve(subgraph.
size());
454 for (
const auto &
e : subgraph) {
455 const auto factor = gfg[
e.index];
456 subgraphFactors->
push_back(clone ? factor->clone() : factor);
458 return subgraphFactors;
462 std::pair<GaussianFactorGraph::shared_ptr, GaussianFactorGraph::shared_ptr>
469 auto remaining = boost::make_shared<GaussianFactorGraph>(factorGraph);
471 for (
const auto &
e : subgraph) {
472 remaining->remove(
e.index);
475 return std::make_pair(subgraphFactors, remaining);
void print(const Matrix &A, const string &s, ostream &stream)
GaussianFactorGraph::shared_ptr buildFactorSubgraph(const GaussianFactorGraph &gfg, const Subgraph &subgraph, const bool clone)
enum gtsam::SubgraphBuilderParameters::Skeleton skeletonType
EdgeIndices edgeIndices() const
static enum @843 ordering
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Fast sampling without replacement.
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
void save(const std::string &fn) const
static vector< size_t > sort_idx(const Container &src)
std::vector< size_t > sample(const std::vector< double > &weights, const size_t t) const
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
std::pair< GaussianFactorGraph::shared_ptr, GaussianFactorGraph::shared_ptr > splitFactorGraph(const GaussianFactorGraph &factorGraph, const Subgraph &subgraph)
size_t size() const
The number of variable entries. This is equal to the number of unique variable Keys.
A faster implementation for DSF, which uses vector rather than btree.
std::vector< double > Weights
size_t find(size_t key) const
Find the label of the set in which {key} lives.
constexpr int first(int i)
Implementation details for constexpr functions.
std::vector< size_t > natural_chain(const GaussianFactorGraph &gfg) const
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Eigen::Triplet< double > T
static Subgraph load(const std::string &fn)
std::vector< size_t > kruskal(const GaussianFactorGraph &gfg, const FastMap< Key, size_t > &ordering, const std::vector< double > &weights) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const mpreal sum(const mpreal tab[], const unsigned long int n, int &status, mp_rnd_t mode=mpreal::get_default_rnd())
virtual Subgraph operator()(const GaussianFactorGraph &jfg) const
EIGEN_DEVICE_FUNC const Scalar & q
Linear Factor Graph where all factors are Gaussians.
const Edges & edges() const
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
std::vector< size_t > buildTree(const GaussianFactorGraph &gfg, const FastMap< Key, size_t > &ordering, const std::vector< double > &weights) const
A thin wrapper around std::map that uses boost's fast_pool_allocator.
ofstream os("timeSchurFactors.csv")
EIGEN_DEVICE_FUNC SegmentReturnType head(Index n)
This is the const version of head(Index).
const KeyVector & keys() const
Access the factor's involved variable keys.
std::vector< size_t > sampleWithoutReplacement(size_t numSamples, const std::vector< double > &weights)
static AugmentationWeight augmentationWeightTranslator(const std::string &s)
void merge(const size_t &i1, const size_t &i2)
Merge the sets containing i1 and i2. Does nothing if i1 and i2 are already in the same set...
std::vector< size_t > unary(const GaussianFactorGraph &gfg) const
static Skeleton skeletonTranslator(const std::string &s)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
friend std::ostream & operator<<(std::ostream &os, const Subgraph &subgraph)
static Ordering Natural(const FACTOR_GRAPH &fg)
Return a natural Ordering. Typically used by iterative solvers.
std::uint64_t Key
Integer nonlinear key type.
Weights weights(const GaussianFactorGraph &gfg) const
std::vector< size_t > bfs(const GaussianFactorGraph &gfg) const
static SkeletonWeight skeletonWeightTranslator(const std::string &s)