diff --git a/gtsam/base/DSFVector.cpp b/gtsam/base/DSFVector.cpp index 454dea45b..25f794b4e 100644 --- a/gtsam/base/DSFVector.cpp +++ b/gtsam/base/DSFVector.cpp @@ -79,7 +79,7 @@ DSFVector::DSFVector(const boost::shared_ptr& v_in, /* ************************************************************************* */ bool DSFVector::isSingleton(const size_t& label) const { bool result = false; - BOOST_FOREACH(size_t key,keys_) { + for(size_t key: keys_) { if (find(key) == label) { if (!result) // find the first occurrence result = true; @@ -93,7 +93,7 @@ bool DSFVector::isSingleton(const size_t& label) const { /* ************************************************************************* */ std::set DSFVector::set(const size_t& label) const { std::set < size_t > set; - BOOST_FOREACH(size_t key,keys_) + for(size_t key: keys_) if (find(key) == label) set.insert(key); return set; @@ -102,7 +102,7 @@ std::set DSFVector::set(const size_t& label) const { /* ************************************************************************* */ std::map > DSFVector::sets() const { std::map > sets; - BOOST_FOREACH(size_t key,keys_) + for(size_t key: keys_) sets[find(key)].insert(key); return sets; } @@ -110,7 +110,7 @@ std::map > DSFVector::sets() const { /* ************************************************************************* */ std::map > DSFVector::arrays() const { std::map > arrays; - BOOST_FOREACH(size_t key,keys_) + for(size_t key: keys_) arrays[find(key)].push_back(key); return arrays; } diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index a9d521a7f..7768a48d3 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -190,7 +190,7 @@ istream& operator>>(istream& inputStream, Matrix& destinationMatrix) { // Copy coefficients to matrix destinationMatrix.resize(height, width); int row = 0; - BOOST_FOREACH(const vector& rowVec, coeffs) { + for(const vector& rowVec: coeffs) { destinationMatrix.row(row) = Eigen::Map(&rowVec[0], width); ++ row; } @@ -419,7 +419,7 @@ Matrix stack(size_t nrMatrices, ...) Matrix stack(const std::vector& blocks) { if (blocks.size() == 1) return blocks.at(0); DenseIndex nrows = 0, ncols = blocks.at(0).cols(); - BOOST_FOREACH(const Matrix& mat, blocks) { + for(const Matrix& mat: blocks) { nrows += mat.rows(); if (ncols != mat.cols()) throw invalid_argument("Matrix::stack(): column size mismatch!"); @@ -427,7 +427,7 @@ Matrix stack(const std::vector& blocks) { Matrix result(nrows, ncols); DenseIndex cur_row = 0; - BOOST_FOREACH(const Matrix& mat, blocks) { + for(const Matrix& mat: blocks) { result.middleRows(cur_row, mat.rows()) = mat; cur_row += mat.rows(); } @@ -441,7 +441,7 @@ Matrix collect(const std::vector& matrices, size_t m, size_t n) size_t dimA1 = m; size_t dimA2 = n*matrices.size(); if (!m && !n) { - BOOST_FOREACH(const Matrix* M, matrices) { + for(const Matrix* M: matrices) { dimA1 = M->rows(); // TODO: should check if all the same ! dimA2 += M->cols(); } @@ -450,7 +450,7 @@ Matrix collect(const std::vector& matrices, size_t m, size_t n) // stl::copy version Matrix A(dimA1, dimA2); size_t hindex = 0; - BOOST_FOREACH(const Matrix* M, matrices) { + for(const Matrix* M: matrices) { size_t row_len = M->cols(); A.block(0, hindex, dimA1, row_len) = *M; hindex += row_len; @@ -611,7 +611,7 @@ std::string formatMatrixIndented(const std::string& label, const Matrix& matrix, boost::tokenizer > tok(matrixStr, boost::char_separator("\n")); DenseIndex row = 0; - BOOST_FOREACH(const std::string& line, tok) + for(const std::string& line: tok) { assert(row < effectiveRows); if(row > 0) diff --git a/gtsam/base/TestableAssertions.h b/gtsam/base/TestableAssertions.h index f976be0e7..8792be0e6 100644 --- a/gtsam/base/TestableAssertions.h +++ b/gtsam/base/TestableAssertions.h @@ -20,7 +20,6 @@ #include #include -#include #include #include #include @@ -91,7 +90,7 @@ bool assert_equal(const std::vector& expected, const std::vector& actual, match = false; if(match) { size_t i = 0; - BOOST_FOREACH(const V& a, expected) { + for(const V& a: expected) { if (!assert_equal(a, actual[i++], tol)) { match = false; break; @@ -100,9 +99,9 @@ bool assert_equal(const std::vector& expected, const std::vector& actual, } if(!match) { std::cout << "expected: " << std::endl; - BOOST_FOREACH(const V& a, expected) { std::cout << a << " "; } + for(const V& a: expected) { std::cout << a << " "; } std::cout << "\nactual: " << std::endl; - BOOST_FOREACH(const V& a, actual) { std::cout << a << " "; } + for(const V& a: actual) { std::cout << a << " "; } std::cout << std::endl; return false; } @@ -133,12 +132,12 @@ bool assert_container_equal(const std::map& expected, const std::map& expected, const std::map< } if(!match) { std::cout << "expected: " << std::endl; - BOOST_FOREACH(const typename Map::value_type& a, expected) { + for(const typename Map::value_type& a: expected) { std::cout << "Key: " << a.first << std::endl; a.second.print(" value"); } std::cout << "\nactual: " << std::endl; - BOOST_FOREACH(const typename Map::value_type& a, actual) { + for(const typename Map::value_type& a: actual) { std::cout << "Key: " << a.first << std::endl; a.second.print(" value"); } @@ -210,12 +209,12 @@ bool assert_container_equal(const std::vector >& expected, } if(!match) { std::cout << "expected: " << std::endl; - BOOST_FOREACH(const typename VectorPair::value_type& a, expected) { + for(const typename VectorPair::value_type& a: expected) { a.first.print( " first "); a.second.print(" second"); } std::cout << "\nactual: " << std::endl; - BOOST_FOREACH(const typename VectorPair::value_type& a, actual) { + for(const typename VectorPair::value_type& a: actual) { a.first.print( " first "); a.second.print(" second"); } @@ -247,9 +246,9 @@ bool assert_container_equal(const V& expected, const V& actual, double tol = 1e- } if(!match) { std::cout << "expected: " << std::endl; - BOOST_FOREACH(const typename V::value_type& a, expected) { a.print(" "); } + for(const typename V::value_type& a: expected) { a.print(" "); } std::cout << "\nactual: " << std::endl; - BOOST_FOREACH(const typename V::value_type& a, actual) { a.print(" "); } + for(const typename V::value_type& a: actual) { a.print(" "); } std::cout << std::endl; return false; } @@ -279,12 +278,12 @@ bool assert_container_equality(const std::map& expected, const std::m } if(!match) { std::cout << "expected: " << std::endl; - BOOST_FOREACH(const typename Map::value_type& a, expected) { + for(const typename Map::value_type& a: expected) { std::cout << "Key: " << a.first << std::endl; std::cout << "Value: " << a.second << std::endl; } std::cout << "\nactual: " << std::endl; - BOOST_FOREACH(const typename Map::value_type& a, actual) { + for(const typename Map::value_type& a: actual) { std::cout << "Key: " << a.first << std::endl; std::cout << "Value: " << a.second << std::endl; } @@ -316,9 +315,9 @@ bool assert_container_equality(const V& expected, const V& actual) { } if(!match) { std::cout << "expected: " << std::endl; - BOOST_FOREACH(const typename V::value_type& a, expected) { std::cout << a << " "; } + for(const typename V::value_type& a: expected) { std::cout << a << " "; } std::cout << "\nactual: " << std::endl; - BOOST_FOREACH(const typename V::value_type& a, actual) { std::cout << a << " "; } + for(const typename V::value_type& a: actual) { std::cout << a << " "; } std::cout << std::endl; return false; } diff --git a/gtsam/base/Vector.cpp b/gtsam/base/Vector.cpp index 40d819de9..8f17e4c6e 100644 --- a/gtsam/base/Vector.cpp +++ b/gtsam/base/Vector.cpp @@ -17,7 +17,6 @@ */ #include -#include #include #include #include @@ -264,12 +263,12 @@ weightedPseudoinverse(const Vector& a, const Vector& weights) { Vector concatVectors(const std::list& vs) { size_t dim = 0; - BOOST_FOREACH(Vector v, vs) + for(Vector v: vs) dim += v.size(); Vector A(dim); size_t index = 0; - BOOST_FOREACH(Vector v, vs) { + for(Vector v: vs) { for(int d = 0; d < v.size(); d++) A(d+index) = v(d); index += v.size(); diff --git a/gtsam/base/tests/testDSFVector.cpp b/gtsam/base/tests/testDSFVector.cpp index d900e1779..66d6889c4 100644 --- a/gtsam/base/tests/testDSFVector.cpp +++ b/gtsam/base/tests/testDSFVector.cpp @@ -70,7 +70,7 @@ TEST(DSFBase, mergePairwiseMatches) { // Merge matches DSFBase dsf(7); // We allow for keys 0..6 - BOOST_FOREACH(const Match& m, matches) + for(const Match& m: matches) dsf.merge(m.first,m.second); // Each point is now associated with a set, represented by one of its members @@ -206,7 +206,7 @@ TEST(DSFVector, mergePairwiseMatches) { // Merge matches DSFVector dsf(keys); - BOOST_FOREACH(const Match& m, matches) + for(const Match& m: matches) dsf.merge(m.first,m.second); // Check that we have two connected components, 1,2,3 and 4,5,6 diff --git a/gtsam/base/tests/testMatrix.cpp b/gtsam/base/tests/testMatrix.cpp index 093f22961..4abc0f81f 100644 --- a/gtsam/base/tests/testMatrix.cpp +++ b/gtsam/base/tests/testMatrix.cpp @@ -919,7 +919,7 @@ TEST(Matrix, weighted_elimination ) // unpack and verify i = 0; - BOOST_FOREACH(boost::tie(r, di, sigma), solution){ + for(boost::tie(r, di, sigma): solution){ EXPECT(assert_equal(r, expectedR.row(i))); // verify r DOUBLES_EQUAL(d(i), di, 1e-8); // verify d DOUBLES_EQUAL(newSigmas(i), sigma, 1e-5); // verify sigma diff --git a/gtsam/base/timing.cpp b/gtsam/base/timing.cpp index b76746ba0..ac58fcca7 100644 --- a/gtsam/base/timing.cpp +++ b/gtsam/base/timing.cpp @@ -20,7 +20,6 @@ #include #include -#include #include #include @@ -66,7 +65,7 @@ TimingOutline::TimingOutline(const std::string& label, size_t id) : size_t TimingOutline::time() const { size_t time = 0; bool hasChildren = false; - BOOST_FOREACH(const ChildMap::value_type& child, children_) { + for(const ChildMap::value_type& child: children_) { time += child.second->time(); hasChildren = true; } @@ -86,11 +85,11 @@ void TimingOutline::print(const std::string& outline) const { // Order children typedef FastMap > ChildOrder; ChildOrder childOrder; - BOOST_FOREACH(const ChildMap::value_type& child, children_) { + for(const ChildMap::value_type& child: children_) { childOrder[child.second->myOrder_] = child.second; } // Print children - BOOST_FOREACH(const ChildOrder::value_type order_child, childOrder) { + for(const ChildOrder::value_type order_child: childOrder) { std::string childOutline(outline); childOutline += "| "; order_child.second->print(childOutline); @@ -130,7 +129,7 @@ void TimingOutline::print2(const std::string& outline, std::cout << std::endl; } - BOOST_FOREACH(const ChildMap::value_type& child, children_) { + for(const ChildMap::value_type& child: children_) { std::string childOutline(outline); if (n_ == 0) { child.second->print2(childOutline, childTotal); @@ -210,7 +209,7 @@ void TimingOutline::finishedIteration() { if (tMin_ == 0 || tIt_ < tMin_) tMin_ = tIt_; tIt_ = 0; - BOOST_FOREACH(ChildMap::value_type& child, children_) { + for(ChildMap::value_type& child: children_) { child.second->finishedIteration(); } } diff --git a/gtsam/base/treeTraversal-inst.h b/gtsam/base/treeTraversal-inst.h index 12a29e45b..0d670ba2e 100644 --- a/gtsam/base/treeTraversal-inst.h +++ b/gtsam/base/treeTraversal-inst.h @@ -29,7 +29,6 @@ #include #include #include -#include #include namespace gtsam { @@ -91,7 +90,7 @@ void DepthFirstForest(FOREST& forest, DATA& rootData, VISITOR_PRE& visitorPre, // Add roots to stack (insert such that they are visited and processed in order { typename Stack::iterator insertLocation = stack.begin(); - BOOST_FOREACH(const sharedNode& root, forest.roots()) + for(const sharedNode& root: forest.roots()) stack.insert(insertLocation, TraversalNode(root, rootData)); } @@ -112,7 +111,7 @@ void DepthFirstForest(FOREST& forest, DATA& rootData, VISITOR_PRE& visitorPre, node.dataPointer = dataList.insert(dataList.end(), visitorPre(node.treeNode, node.parentData)); typename Stack::iterator insertLocation = stack.begin(); - BOOST_FOREACH(const sharedNode& child, node.treeNode->children) + for(const sharedNode& child: node.treeNode->children) stack.insert(insertLocation, TraversalNode(child, *node.dataPointer)); node.expanded = true; } diff --git a/gtsam/base/treeTraversal/parallelTraversalTasks.h b/gtsam/base/treeTraversal/parallelTraversalTasks.h index c1df47a01..70a9b1cf1 100644 --- a/gtsam/base/treeTraversal/parallelTraversalTasks.h +++ b/gtsam/base/treeTraversal/parallelTraversalTasks.h @@ -101,7 +101,7 @@ namespace gtsam { tbb::task* firstChild = 0; tbb::task_list childTasks; - BOOST_FOREACH(const boost::shared_ptr& child, treeNode->children) + for(const boost::shared_ptr& child: treeNode->children) { // Process child in a subtask. Important: Run visitorPre before calling // allocate_child so that if visitorPre throws an exception, we will not have @@ -143,7 +143,7 @@ namespace gtsam { void processNodeRecursively(const boost::shared_ptr& node, DATA& myData) { - BOOST_FOREACH(const boost::shared_ptr& child, node->children) + for(const boost::shared_ptr& child: node->children) { DATA childData = visitorPre(child, myData); processNodeRecursively(child, childData); @@ -174,7 +174,7 @@ namespace gtsam { typedef PreOrderTask PreOrderTask; // Create data and tasks for our children tbb::task_list tasks; - BOOST_FOREACH(const boost::shared_ptr& root, roots) + for(const boost::shared_ptr& root: roots) { boost::shared_ptr rootData = boost::allocate_shared(tbb::scalable_allocator(), visitorPre(root, myData)); tasks.push_back(*new(allocate_child()) diff --git a/gtsam/base/treeTraversal/statistics.h b/gtsam/base/treeTraversal/statistics.h index 805c69758..7a5c7d256 100644 --- a/gtsam/base/treeTraversal/statistics.h +++ b/gtsam/base/treeTraversal/statistics.h @@ -63,7 +63,7 @@ namespace gtsam { { int largestProblemSize = 0; int secondLargestProblemSize = 0; - BOOST_FOREACH(const boost::shared_ptr& child, node->children) + for(const boost::shared_ptr& child: node->children) { if (child->problemSize() > largestProblemSize) { diff --git a/gtsam/discrete/Assignment.h b/gtsam/discrete/Assignment.h index 709c7350e..3665d6dfa 100644 --- a/gtsam/discrete/Assignment.h +++ b/gtsam/discrete/Assignment.h @@ -18,7 +18,6 @@ #pragma once -#include #include #include #include @@ -36,7 +35,7 @@ namespace gtsam { public: void print(const std::string& s = "Assignment: ") const { std::cout << s << ": "; - BOOST_FOREACH(const typename Assignment::value_type& keyValue, *this) + for(const typename Assignment::value_type& keyValue: *this) std::cout << "(" << keyValue.first << ", " << keyValue.second << ")"; std::cout << std::endl; } @@ -65,7 +64,7 @@ namespace gtsam { std::vector > allPossValues; Assignment values; typedef std::pair DiscreteKey; - BOOST_FOREACH(const DiscreteKey& key, keys) + for(const DiscreteKey& key: keys) values[key.first] = 0; //Initialize from 0 while (1) { allPossValues.push_back(values); diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index c1648888e..ecc8533c1 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -24,7 +24,6 @@ #include #include -#include #include #include using boost::assign::operator+=; @@ -310,7 +309,7 @@ namespace gtsam { label_(label), allSame_(true) { branches_.reserve(f.branches_.size()); // reserve space - BOOST_FOREACH (const NodePtr& branch, f.branches_) + for (const NodePtr& branch: f.branches_) push_back(branch->apply(op)); } @@ -332,7 +331,7 @@ namespace gtsam { // If second argument of binary op is Leaf node, recurse on branches NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const { boost::shared_ptr h(new Choice(label(), nrChoices())); - BOOST_FOREACH(NodePtr branch, branches_) + for(NodePtr branch: branches_) h->push_back(fL.apply_f_op_g(*branch, op)); return Unique(h); } @@ -347,7 +346,7 @@ namespace gtsam { template NodePtr apply_fC_op_gL(const Leaf& gL, OP op) const { boost::shared_ptr h(new Choice(label(), nrChoices())); - BOOST_FOREACH(const NodePtr& branch, branches_) + for(const NodePtr& branch: branches_) h->push_back(branch->apply_f_op_g(gL, op)); return Unique(h); } @@ -359,7 +358,7 @@ namespace gtsam { // second case, not label of interest, just recurse boost::shared_ptr r(new Choice(label_, branches_.size())); - BOOST_FOREACH(const NodePtr& branch, branches_) + for(const NodePtr& branch: branches_) r->push_back(branch->choose(label, index)); return Unique(r); } @@ -593,7 +592,7 @@ namespace gtsam { // put together via Shannon expansion otherwise not sorted. std::vector functions; - BOOST_FOREACH(const MXNodePtr& branch, choice->branches()) { + for(const MXNodePtr& branch: choice->branches()) { LY converted(convert(branch, map, op)); functions += converted; } diff --git a/gtsam/discrete/DecisionTreeFactor.cpp b/gtsam/discrete/DecisionTreeFactor.cpp index 9ed88bc3d..dd26cbfa9 100644 --- a/gtsam/discrete/DecisionTreeFactor.cpp +++ b/gtsam/discrete/DecisionTreeFactor.cpp @@ -66,11 +66,11 @@ namespace gtsam { ADT::Binary op) const { map cs; // new cardinalities // make unique key-cardinality map - BOOST_FOREACH(Key j, keys()) cs[j] = cardinality(j); - BOOST_FOREACH(Key j, f.keys()) cs[j] = f.cardinality(j); + for(Key j: keys()) cs[j] = cardinality(j); + for(Key j: f.keys()) cs[j] = f.cardinality(j); // Convert map into keys DiscreteKeys keys; - BOOST_FOREACH(const DiscreteKey& key, cs) + for(const DiscreteKey& key: cs) keys.push_back(key); // apply operand ADT result = ADT::apply(f, op); diff --git a/gtsam/discrete/DiscreteBayesNet.cpp b/gtsam/discrete/DiscreteBayesNet.cpp index 3b3939674..55a266e77 100644 --- a/gtsam/discrete/DiscreteBayesNet.cpp +++ b/gtsam/discrete/DiscreteBayesNet.cpp @@ -46,7 +46,7 @@ namespace gtsam { double DiscreteBayesNet::evaluate(const DiscreteConditional::Values & values) const { // evaluate all conditionals and multiply double result = 1.0; - BOOST_FOREACH(DiscreteConditional::shared_ptr conditional, *this) + for(DiscreteConditional::shared_ptr conditional: *this) result *= (*conditional)(values); return result; } diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index f21a705ff..4a918ef02 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -87,7 +87,7 @@ bool DiscreteConditional::equals(const DiscreteFactor& other, Potentials::ADT DiscreteConditional::choose(const Values& parentsValues) const { ADT pFS(*this); Key j; size_t value; - BOOST_FOREACH(Key key, parents()) + for(Key key: parents()) try { j = (key); value = parentsValues.at(j); @@ -111,7 +111,7 @@ void DiscreteConditional::solveInPlace(Values& values) const { double maxP = 0; DiscreteKeys keys; - BOOST_FOREACH(Key idx, frontals()) { + for(Key idx: frontals()) { DiscreteKey dk(idx, cardinality(idx)); keys & dk; } @@ -119,7 +119,7 @@ void DiscreteConditional::solveInPlace(Values& values) const { vector allPosbValues = cartesianProduct(keys); // Find the MPE - BOOST_FOREACH(Values& frontalVals, allPosbValues) { + for(Values& frontalVals: allPosbValues) { double pValueS = pFS(frontalVals); // P(F=value|S=parentsValues) // Update MPE solution if better if (pValueS > maxP) { @@ -129,7 +129,7 @@ void DiscreteConditional::solveInPlace(Values& values) const { } //set values (inPlace) to mpe - BOOST_FOREACH(Key j, frontals()) { + for(Key j: frontals()) { values[j] = mpe[j]; } } diff --git a/gtsam/discrete/DiscreteFactorGraph.cpp b/gtsam/discrete/DiscreteFactorGraph.cpp index c2128c776..af11d4b14 100644 --- a/gtsam/discrete/DiscreteFactorGraph.cpp +++ b/gtsam/discrete/DiscreteFactorGraph.cpp @@ -41,7 +41,7 @@ namespace gtsam { /* ************************************************************************* */ KeySet DiscreteFactorGraph::keys() const { KeySet keys; - BOOST_FOREACH(const sharedFactor& factor, *this) + for(const sharedFactor& factor: *this) if (factor) keys.insert(factor->begin(), factor->end()); return keys; } @@ -49,7 +49,7 @@ namespace gtsam { /* ************************************************************************* */ DecisionTreeFactor DiscreteFactorGraph::product() const { DecisionTreeFactor result; - BOOST_FOREACH(const sharedFactor& factor, *this) + for(const sharedFactor& factor: *this) if (factor) result = (*factor) * result; return result; } @@ -58,7 +58,7 @@ namespace gtsam { double DiscreteFactorGraph::operator()( const DiscreteFactor::Values &values) const { double product = 1.0; - BOOST_FOREACH( const sharedFactor& factor, factors_ ) + for( const sharedFactor& factor: factors_ ) product *= (*factor)(values); return product; } @@ -78,7 +78,7 @@ namespace gtsam { // /* ************************************************************************* */ // void DiscreteFactorGraph::permuteWithInverse( // const Permutation& inversePermutation) { -// BOOST_FOREACH(const sharedFactor& factor, factors_) { +// for(const sharedFactor& factor: factors_) { // if(factor) // factor->permuteWithInverse(inversePermutation); // } @@ -87,7 +87,7 @@ namespace gtsam { // /* ************************************************************************* */ // void DiscreteFactorGraph::reduceWithInverse( // const internal::Reduction& inverseReduction) { -// BOOST_FOREACH(const sharedFactor& factor, factors_) { +// for(const sharedFactor& factor: factors_) { // if(factor) // factor->reduceWithInverse(inverseReduction); // } @@ -107,7 +107,7 @@ namespace gtsam { // PRODUCT: multiply all factors gttic(product); DecisionTreeFactor product; - BOOST_FOREACH(const DiscreteFactor::shared_ptr& factor, factors) + for(const DiscreteFactor::shared_ptr& factor: factors) product = (*factor) * product; gttoc(product); diff --git a/gtsam/discrete/DiscreteKey.cpp b/gtsam/discrete/DiscreteKey.cpp index 828a93eec..b4fd2e5a1 100644 --- a/gtsam/discrete/DiscreteKey.cpp +++ b/gtsam/discrete/DiscreteKey.cpp @@ -18,7 +18,6 @@ #include #include // for key names -#include // FOREACH #include "DiscreteKey.h" namespace gtsam { @@ -34,7 +33,7 @@ namespace gtsam { vector DiscreteKeys::indices() const { vector < Key > js; - BOOST_FOREACH(const DiscreteKey& key, *this) + for(const DiscreteKey& key: *this) js.push_back(key.first); return js; } @@ -42,7 +41,7 @@ namespace gtsam { map DiscreteKeys::cardinalities() const { map cs; cs.insert(begin(),end()); -// BOOST_FOREACH(const DiscreteKey& key, *this) +// for(const DiscreteKey& key: *this) // cs.insert(key); return cs; } diff --git a/gtsam/discrete/Potentials.cpp b/gtsam/discrete/Potentials.cpp index 11dddee66..c4cdbe0ef 100644 --- a/gtsam/discrete/Potentials.cpp +++ b/gtsam/discrete/Potentials.cpp @@ -54,7 +54,7 @@ namespace gtsam { void Potentials::print(const string& s, const KeyFormatter& formatter) const { cout << s << "\n Cardinalities: "; - BOOST_FOREACH(const DiscreteKey& key, cardinalities_) + for(const DiscreteKey& key: cardinalities_) cout << formatter(key.first) << "=" << formatter(key.second) << " "; cout << endl; ADT::print(" "); @@ -68,11 +68,11 @@ namespace gtsam { // map ordering; // // // Get the original keys from cardinalities_ -// BOOST_FOREACH(const DiscreteKey& key, cardinalities_) +// for(const DiscreteKey& key: cardinalities_) // keys & key; // // // Perform Permutation -// BOOST_FOREACH(DiscreteKey& key, keys) { +// for(DiscreteKey& key: keys) { // ordering[key.first] = remapping[key.first]; // key.first = ordering[key.first]; // } diff --git a/gtsam/discrete/Signature.cpp b/gtsam/discrete/Signature.cpp index 9e63b957d..0ee5c63b8 100644 --- a/gtsam/discrete/Signature.cpp +++ b/gtsam/discrete/Signature.cpp @@ -17,7 +17,6 @@ */ #include -#include #include "Signature.h" @@ -125,7 +124,7 @@ namespace gtsam { DiscreteKeys Signature::discreteKeysParentsFirst() const { DiscreteKeys keys; - BOOST_FOREACH(const DiscreteKey& key, parents_) + for(const DiscreteKey& key: parents_) keys.push_back(key); keys.push_back(key_); return keys; @@ -134,7 +133,7 @@ namespace gtsam { vector Signature::indices() const { vector js; js.push_back(key_.first); - BOOST_FOREACH(const DiscreteKey& key, parents_) + for(const DiscreteKey& key: parents_) js.push_back(key.first); return js; } @@ -142,8 +141,8 @@ namespace gtsam { vector Signature::cpt() const { vector cpt; if (table_) { - BOOST_FOREACH(const Row& row, *table_) - BOOST_FOREACH(const double& x, row) + for(const Row& row: *table_) + for(const double& x: row) cpt.push_back(x); } return cpt; @@ -171,7 +170,7 @@ namespace gtsam { // qi::phrase_parse(f, l, parser::grammar.table, qi::space, table); // using full grammar parser::parse_table(spec, table); if (success) { - BOOST_FOREACH(Row& row, table) + for(Row& row: table) normalize(row); table_.reset(table); } @@ -180,7 +179,7 @@ namespace gtsam { Signature& Signature::operator=(const Table& t) { Table table = t; - BOOST_FOREACH(Row& row, table) + for(Row& row: table) normalize(row); table_.reset(table); return *this; diff --git a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp index d6902bbef..9c3f4bd63 100644 --- a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp +++ b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp @@ -25,7 +25,6 @@ #define DISABLE_TIMING #include -#include #include #include #include @@ -66,7 +65,7 @@ void dot(const T&f, const string& filename) { typename DecisionTree::Node::Ptr DecisionTree::Choice::apply_fC_op_gL( Cache& cache, const Leaf& gL, Mul op) const { Ptr h(new Choice(label(), cardinality())); - BOOST_FOREACH(const NodePtr& branch, branches_) + for(const NodePtr& branch: branches_) h->push_back(branch->apply_f_op_g(cache, gL, op)); return Unique(cache, h); } @@ -401,7 +400,7 @@ TEST(ADT, constructor) DiscreteKey z0(0,5), z1(1,4), z2(2,3), z3(3,2); vector table(5 * 4 * 3 * 2); double x = 0; - BOOST_FOREACH(double& t, table) + for(double& t: table) t = x++; ADT f3(z0 & z1 & z2 & z3, table); Assignment assignment; diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index c1acaf83d..93126f642 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -63,7 +63,7 @@ //// double evaluate(const DiscreteConditional::Values & values) { //// double result = (*(this->conditional_))(values); //// // evaluate all children and multiply into result -//// BOOST_FOREACH(boost::shared_ptr c, children_) +//// for(boost::shared_ptr c: children_) //// result *= c->evaluate(values); //// return result; //// } @@ -213,7 +213,7 @@ // // // calculate all shortcuts to root // DiscreteBayesTree::Nodes cliques = bayesTree.nodes(); -// BOOST_FOREACH(Clique::shared_ptr c, cliques) { +// for(Clique::shared_ptr c: cliques) { // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); // if (debug) { // c->printSignature(); diff --git a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp index 052180f7a..0fbf44097 100644 --- a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp +++ b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp @@ -321,7 +321,7 @@ struct Graph2: public std::list { /** Add a factor graph*/ // void operator +=(const Graph2& graph) { -// BOOST_FOREACH(const Factor2& f, graph) +// for(const Factor2& f: graph) // push_back(f); // } friend std::ostream& operator <<(std::ostream &os, const Graph2& graph); @@ -334,7 +334,7 @@ friend std::ostream& operator <<(std::ostream &os, const Graph2& graph); // return graph; //} std::ostream& operator <<(std::ostream &os, const Graph2& graph) { -BOOST_FOREACH(const Factor2& f, graph) +for(const Factor2& f: graph) os << f << endl; return os; } diff --git a/gtsam/geometry/Pose2.cpp b/gtsam/geometry/Pose2.cpp index 8a0e8fbf5..34b146bee 100644 --- a/gtsam/geometry/Pose2.cpp +++ b/gtsam/geometry/Pose2.cpp @@ -19,8 +19,6 @@ #include #include -#include - #include #include #include @@ -314,7 +312,7 @@ boost::optional align(const vector& pairs) { // calculate centroids Point2 cp,cq; - BOOST_FOREACH(const Point2Pair& pair, pairs) { + for(const Point2Pair& pair: pairs) { cp += pair.first; cq += pair.second; } @@ -323,7 +321,7 @@ boost::optional align(const vector& pairs) { // calculate cos and sin double c=0,s=0; - BOOST_FOREACH(const Point2Pair& pair, pairs) { + for(const Point2Pair& pair: pairs) { Point2 dq = pair.first - cp; Point2 dp = pair.second - cq; c += dp.x() * dq.x() + dp.y() * dq.y(); diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index d170282fe..3138dfd64 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -19,7 +19,6 @@ #include #include -#include #include #include @@ -424,7 +423,7 @@ boost::optional Pose3::Align(const std::vector& abPointPairs) boost::optional align(const vector& baPointPairs) { vector abPointPairs; - BOOST_FOREACH (const Point3Pair& baPair, baPointPairs) { + for (const Point3Pair& baPair: baPointPairs) { abPointPairs.push_back(make_pair(baPair.second, baPair.first)); } return Pose3::Align(abPointPairs); diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index 0e99268ee..912b26262 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -33,7 +33,6 @@ #include #include -#include #include #include #include @@ -56,7 +55,7 @@ TEST(Unit3, point3) { ps += Point3(1, 0, 0), Point3(0, 1, 0), Point3(0, 0, 1), Point3(1, 1, 0) / sqrt(2.0); Matrix actualH, expectedH; - BOOST_FOREACH(Point3 p,ps) { + for(Point3 p: ps) { Unit3 s(p); expectedH = numericalDerivative11(point3_, s); EXPECT(assert_equal(p, s.point3(actualH), 1e-8)); diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 4e8ae2f17..369c54bea 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -237,7 +237,7 @@ Point3 triangulatePoint3(const std::vector& poses, // construct projection matrices from poses & calibration std::vector projection_matrices; CameraProjectionMatrix createP(*sharedCal); // partially apply - BOOST_FOREACH(const Pose3& pose, poses) + for(const Pose3& pose: poses) projection_matrices.push_back(createP(pose)); // Triangulate linearly @@ -250,7 +250,7 @@ Point3 triangulatePoint3(const std::vector& poses, #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION // verify that the triangulated point lies in front of all cameras - BOOST_FOREACH(const Pose3& pose, poses) { + for(const Pose3& pose: poses) { const Point3& p_local = pose.transform_to(point); if (p_local.z() <= 0) throw(TriangulationCheiralityException()); @@ -286,7 +286,7 @@ Point3 triangulatePoint3( // construct projection matrices from poses & calibration std::vector projection_matrices; - BOOST_FOREACH(const CAMERA& camera, cameras) + for(const CAMERA& camera: cameras) projection_matrices.push_back( CameraProjectionMatrix(camera.calibration())( camera.pose())); @@ -298,7 +298,7 @@ Point3 triangulatePoint3( #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION // verify that the triangulated point lies in front of all cameras - BOOST_FOREACH(const CAMERA& camera, cameras) { + for(const CAMERA& camera: cameras) { const Point3& p_local = camera.pose().transform_to(point); if (p_local.z() <= 0) throw(TriangulationCheiralityException()); @@ -454,7 +454,7 @@ TriangulationResult triangulateSafe(const std::vector& cameras, // Check landmark distance and re-projection errors to avoid outliers size_t i = 0; double totalReprojError = 0.0; - BOOST_FOREACH(const CAMERA& camera, cameras) { + for(const CAMERA& camera: cameras) { const Pose3& pose = camera.pose(); if (params.landmarkDistanceThreshold > 0 && distance(pose.translation(), point) diff --git a/gtsam/inference/BayesNet-inst.h b/gtsam/inference/BayesNet-inst.h index f5e69fcce..d95c5f2e2 100644 --- a/gtsam/inference/BayesNet-inst.h +++ b/gtsam/inference/BayesNet-inst.h @@ -44,7 +44,7 @@ namespace gtsam { typename CONDITIONAL::Frontals frontals = conditional->frontals(); Key me = frontals.front(); typename CONDITIONAL::Parents parents = conditional->parents(); - BOOST_FOREACH(Key p, parents) + for(Key p: parents) of << keyFormatter(p) << "->" << keyFormatter(me) << std::endl; } diff --git a/gtsam/inference/BayesTree-inst.h b/gtsam/inference/BayesTree-inst.h index 3a3e1317c..e04af1339 100644 --- a/gtsam/inference/BayesTree-inst.h +++ b/gtsam/inference/BayesTree-inst.h @@ -26,7 +26,6 @@ #include #include -#include #include #include @@ -38,7 +37,7 @@ namespace gtsam { template BayesTreeCliqueData BayesTree::getCliqueData() const { BayesTreeCliqueData data; - BOOST_FOREACH(const sharedClique& root, roots_) + for(const sharedClique& root: roots_) getCliqueData(data, root); return data; } @@ -48,7 +47,7 @@ namespace gtsam { void BayesTree::getCliqueData(BayesTreeCliqueData& data, sharedClique clique) const { data.conditionalSizes.push_back(clique->conditional()->nrFrontals()); data.separatorSizes.push_back(clique->conditional()->nrParents()); - BOOST_FOREACH(sharedClique c, clique->children) { + for(sharedClique c: clique->children) { getCliqueData(data, c); } } @@ -57,7 +56,7 @@ namespace gtsam { template size_t BayesTree::numCachedSeparatorMarginals() const { size_t count = 0; - BOOST_FOREACH(const sharedClique& root, roots_) + for(const sharedClique& root: roots_) count += root->numCachedSeparatorMarginals(); return count; } @@ -68,7 +67,7 @@ namespace gtsam { if (roots_.empty()) throw std::invalid_argument("the root of Bayes tree has not been initialized!"); std::ofstream of(s.c_str()); of<< "digraph G{\n"; - BOOST_FOREACH(const sharedClique& root, roots_) + for(const sharedClique& root: roots_) saveGraph(of, root, keyFormatter); of<<"}"; of.close(); @@ -84,7 +83,7 @@ namespace gtsam { std::string parent = out.str(); parent += "[label=\""; - BOOST_FOREACH(Key index, clique->conditional_->frontals()) { + for(Key index: clique->conditional_->frontals()) { if(!first) parent += ","; first = false; parent += indexFormatter(index); } @@ -95,7 +94,7 @@ namespace gtsam { } first = true; - BOOST_FOREACH(Key sep, clique->conditional_->parents()) { + for(Key sep: clique->conditional_->parents()) { if(!first) parent += ","; first = false; parent += indexFormatter(sep); } @@ -103,7 +102,7 @@ namespace gtsam { s << parent; parentnum = num; - BOOST_FOREACH(sharedClique c, clique->children) { + for(sharedClique c: clique->children) { num++; saveGraph(s, c, indexFormatter, parentnum); } @@ -113,7 +112,7 @@ namespace gtsam { template size_t BayesTree::size() const { size_t size = 0; - BOOST_FOREACH(const sharedClique& clique, roots_) + for(const sharedClique& clique: roots_) size += clique->treeSize(); return size; } @@ -121,7 +120,7 @@ namespace gtsam { /* ************************************************************************* */ template void BayesTree::addClique(const sharedClique& clique, const sharedClique& parent_clique) { - BOOST_FOREACH(Key j, clique->conditional()->frontals()) + for(Key j: clique->conditional()->frontals()) nodes_[j] = clique; if (parent_clique != NULL) { clique->parent_ = parent_clique; @@ -189,7 +188,7 @@ namespace gtsam { this->clear(); boost::shared_ptr rootContainer = boost::make_shared(); treeTraversal::DepthFirstForest(other, rootContainer, BayesTreeCloneForestVisitorPre); - BOOST_FOREACH(const sharedClique& root, rootContainer->children) { + for(const sharedClique& root: rootContainer->children) { root->parent_ = typename Clique::weak_ptr(); // Reset the parent since it's set to the dummy clique insertRoot(root); } @@ -234,13 +233,13 @@ namespace gtsam { template void BayesTree::fillNodesIndex(const sharedClique& subtree) { // Add each frontal variable of this root node - BOOST_FOREACH(const Key& j, subtree->conditional()->frontals()) { + for(const Key& j: subtree->conditional()->frontals()) { bool inserted = nodes_.insert(std::make_pair(j, subtree)).second; assert(inserted); (void)inserted; } // Fill index for each child typedef typename BayesTree::sharedClique sharedClique; - BOOST_FOREACH(const sharedClique& child, subtree->children) { + for(const sharedClique& child: subtree->children) { fillNodesIndex(child); } } @@ -345,7 +344,7 @@ namespace gtsam { boost::shared_ptr p_C1_B; { FastVector C1_minus_B; { KeySet C1_minus_B_set(C1->conditional()->beginParents(), C1->conditional()->endParents()); - BOOST_FOREACH(const Key j, *B->conditional()) { + for(const Key j: *B->conditional()) { C1_minus_B_set.erase(j); } C1_minus_B.assign(C1_minus_B_set.begin(), C1_minus_B_set.end()); } @@ -357,7 +356,7 @@ namespace gtsam { boost::shared_ptr p_C2_B; { FastVector C2_minus_B; { KeySet C2_minus_B_set(C2->conditional()->beginParents(), C2->conditional()->endParents()); - BOOST_FOREACH(const Key j, *B->conditional()) { + for(const Key j: *B->conditional()) { C2_minus_B_set.erase(j); } C2_minus_B.assign(C2_minus_B_set.begin(), C2_minus_B_set.end()); } @@ -403,7 +402,7 @@ namespace gtsam { /* ************************************************************************* */ template void BayesTree::deleteCachedShortcuts() { - BOOST_FOREACH(const sharedClique& root, roots_) { + for(const sharedClique& root: roots_) { root->deleteCachedShortcuts(); } } @@ -424,10 +423,10 @@ namespace gtsam { } // orphan my children - BOOST_FOREACH(sharedClique child, clique->children) + for(sharedClique child: clique->children) child->parent_ = typename Clique::weak_ptr(); - BOOST_FOREACH(Key j, clique->conditional()->frontals()) { + for(Key j: clique->conditional()->frontals()) { nodes_.unsafe_erase(j); } } @@ -462,7 +461,7 @@ namespace gtsam { void BayesTree::removeTop(const FastVector& keys, BayesNetType& bn, Cliques& orphans) { // process each key of the new factor - BOOST_FOREACH(const Key& j, keys) + for(const Key& j: keys) { // get the clique // TODO: Nodes will be searched again in removeClique @@ -475,7 +474,7 @@ namespace gtsam { // Delete cachedShortcuts for each orphan subtree //TODO: Consider Improving - BOOST_FOREACH(sharedClique& orphan, orphans) + for(sharedClique& orphan: orphans) orphan->deleteCachedShortcuts(); } @@ -499,14 +498,14 @@ namespace gtsam { for(typename Cliques::iterator clique = cliques.begin(); clique != cliques.end(); ++clique) { // Add children - BOOST_FOREACH(const sharedClique& child, (*clique)->children) { + for(const sharedClique& child: (*clique)->children) { cliques.push_back(child); } // Delete cached shortcuts (*clique)->deleteCachedShortcutsNonRecursive(); // Remove this node from the nodes index - BOOST_FOREACH(Key j, (*clique)->conditional()->frontals()) { + for(Key j: (*clique)->conditional()->frontals()) { nodes_.unsafe_erase(j); } // Erase the parent and children pointers diff --git a/gtsam/inference/BayesTree.cpp b/gtsam/inference/BayesTree.cpp index 6d6a4a4d3..2fb0227b6 100644 --- a/gtsam/inference/BayesTree.cpp +++ b/gtsam/inference/BayesTree.cpp @@ -20,7 +20,6 @@ #include -#include #include namespace gtsam { @@ -41,7 +40,7 @@ BayesTreeCliqueStats BayesTreeCliqueData::getStats() const double sum = 0.0; size_t max = 0; - BOOST_FOREACH(size_t s, conditionalSizes) { + for(size_t s: conditionalSizes) { sum += (double)s; if(s > max) max = s; } @@ -50,7 +49,7 @@ BayesTreeCliqueStats BayesTreeCliqueData::getStats() const sum = 0.0; max = 1; - BOOST_FOREACH(size_t s, separatorSizes) { + for(size_t s: separatorSizes) { sum += (double)s; if(s > max) max = s; } diff --git a/gtsam/inference/BayesTreeCliqueBase-inst.h b/gtsam/inference/BayesTreeCliqueBase-inst.h index 256ff983d..31a8c55b6 100644 --- a/gtsam/inference/BayesTreeCliqueBase-inst.h +++ b/gtsam/inference/BayesTreeCliqueBase-inst.h @@ -18,7 +18,6 @@ #include #include -#include namespace gtsam { @@ -83,7 +82,7 @@ namespace gtsam { template size_t BayesTreeCliqueBase::treeSize() const { size_t size = 1; - BOOST_FOREACH(const derived_ptr& child, children) + for(const derived_ptr& child: children) size += child->treeSize(); return size; } @@ -96,7 +95,7 @@ namespace gtsam { return 0; size_t subtree_count = 1; - BOOST_FOREACH(const derived_ptr& child, children) + for(const derived_ptr& child: children) subtree_count += child->numCachedSeparatorMarginals(); return subtree_count; @@ -204,7 +203,7 @@ namespace gtsam { // root are also generated. So, if this clique's cached shortcut is set, // recursively call over all child cliques. Otherwise, it is unnecessary. if (cachedSeparatorMarginal_) { - BOOST_FOREACH(derived_ptr& child, children) { + for(derived_ptr& child: children) { child->deleteCachedShortcuts(); } diff --git a/gtsam/inference/ClusterTree-inst.h b/gtsam/inference/ClusterTree-inst.h index 6b28f2dbf..bd886273a 100644 --- a/gtsam/inference/ClusterTree-inst.h +++ b/gtsam/inference/ClusterTree-inst.h @@ -13,7 +13,6 @@ #include #include -#include #include namespace gtsam { @@ -87,7 +86,7 @@ struct EliminationData { gatheredFactors += myData.childFactors; // Check for Bayes tree orphan subtrees, and add them to our children - BOOST_FOREACH(const sharedFactor& f, node->factors) { + for(const sharedFactor& f: node->factors) { if (const BayesTreeOrphanWrapper* asSubtree = dynamic_cast*>(f.get())) { myData.bayesTreeNode->children.push_back(asSubtree->clique); @@ -107,7 +106,7 @@ struct EliminationData { // Fill nodes index - we do this here instead of calling insertRoot at the end to avoid // putting orphan subtrees in the index - they'll already be in the index of the ISAM2 // object they're added to. - BOOST_FOREACH(const Key& j, myData.bayesTreeNode->conditional()->frontals()) + for(const Key& j: myData.bayesTreeNode->conditional()->frontals()) nodesIndex_.insert(std::make_pair(j, myData.bayesTreeNode)); // Store remaining factor in parent's gathered factors @@ -138,7 +137,7 @@ void ClusterTree::Cluster::mergeChildren( size_t nrNewChildren = 0; // Loop over children size_t i = 0; - BOOST_FOREACH(const sharedNode& child, children) { + for(const sharedNode& child: children) { if (merge[i]) { nrKeys += child->orderedFrontalKeys.size(); nrFactors += child->factors.size(); @@ -155,7 +154,7 @@ void ClusterTree::Cluster::mergeChildren( typename Node::Children newChildren; newChildren.reserve(nrNewChildren); i = 0; - BOOST_FOREACH(const sharedNode& child, children) { + for(const sharedNode& child: children) { if (merge[i]) { // Merge keys. For efficiency, we add keys in reverse order at end, calling reverse after.. orderedFrontalKeys.insert(orderedFrontalKeys.end(), @@ -228,7 +227,7 @@ std::pair, boost::shared_ptr > ClusterTree< remaining->reserve( remainingFactors_.size() + rootsContainer.childFactors.size()); remaining->push_back(remainingFactors_.begin(), remainingFactors_.end()); - BOOST_FOREACH(const sharedFactor& factor, rootsContainer.childFactors) { + for(const sharedFactor& factor: rootsContainer.childFactors) { if (factor) remaining->push_back(factor); } diff --git a/gtsam/inference/Conditional-inst.h b/gtsam/inference/Conditional-inst.h index a22f290d9..39b60079c 100644 --- a/gtsam/inference/Conditional-inst.h +++ b/gtsam/inference/Conditional-inst.h @@ -18,7 +18,6 @@ // \callgraph #pragma once -#include #include #include @@ -29,11 +28,11 @@ namespace gtsam { template void Conditional::print(const std::string& s, const KeyFormatter& formatter) const { std::cout << s << " P("; - BOOST_FOREACH(Key key, frontals()) + for(Key key: frontals()) std::cout << " " << formatter(key); if (nrParents() > 0) std::cout << " |"; - BOOST_FOREACH(Key parent, parents()) + for(Key parent: parents()) std::cout << " " << formatter(parent); std::cout << ")" << std::endl; } diff --git a/gtsam/inference/EliminationTree-inst.h b/gtsam/inference/EliminationTree-inst.h index 68e623b68..90540aaa6 100644 --- a/gtsam/inference/EliminationTree-inst.h +++ b/gtsam/inference/EliminationTree-inst.h @@ -17,7 +17,6 @@ */ #pragma once -#include #include #include #include @@ -66,7 +65,7 @@ namespace gtsam { const std::string& str, const KeyFormatter& keyFormatter) const { std::cout << str << "(" << keyFormatter(key) << ")\n"; - BOOST_FOREACH(const sharedFactor& factor, factors) { + for(const sharedFactor& factor: factors) { if(factor) factor->print(str); else @@ -107,7 +106,7 @@ namespace gtsam { // for row i \in Struct[A*j] do node->children.reserve(factors.size()); node->factors.reserve(factors.size()); - BOOST_FOREACH(const size_t i, factors) { + for(const size_t i: factors) { // If we already hit a variable in this factor, make the subtree containing the previous // variable in this factor a child of the current node. This means that the variables // eliminated earlier in the factor depend on the later variables in the factor. If we @@ -222,15 +221,15 @@ namespace gtsam { // Add roots in sorted order { FastMap keys; - BOOST_FOREACH(const sharedNode& root, this->roots_) { keys.insert(std::make_pair(root->key, root)); } + for(const sharedNode& root: this->roots_) { keys.insert(std::make_pair(root->key, root)); } typedef typename FastMap::value_type Key_Node; - BOOST_FOREACH(const Key_Node& key_node, keys) { stack1.push(key_node.second); } + for(const Key_Node& key_node: keys) { stack1.push(key_node.second); } } { FastMap keys; - BOOST_FOREACH(const sharedNode& root, expected.roots_) { keys.insert(std::make_pair(root->key, root)); } + for(const sharedNode& root: expected.roots_) { keys.insert(std::make_pair(root->key, root)); } typedef typename FastMap::value_type Key_Node; - BOOST_FOREACH(const Key_Node& key_node, keys) { stack2.push(key_node.second); } + for(const Key_Node& key_node: keys) { stack2.push(key_node.second); } } // Traverse, adding children in sorted order @@ -262,15 +261,15 @@ namespace gtsam { // Add children in sorted order { FastMap keys; - BOOST_FOREACH(const sharedNode& node, node1->children) { keys.insert(std::make_pair(node->key, node)); } + for(const sharedNode& node: node1->children) { keys.insert(std::make_pair(node->key, node)); } typedef typename FastMap::value_type Key_Node; - BOOST_FOREACH(const Key_Node& key_node, keys) { stack1.push(key_node.second); } + for(const Key_Node& key_node: keys) { stack1.push(key_node.second); } } { FastMap keys; - BOOST_FOREACH(const sharedNode& node, node2->children) { keys.insert(std::make_pair(node->key, node)); } + for(const sharedNode& node: node2->children) { keys.insert(std::make_pair(node->key, node)); } typedef typename FastMap::value_type Key_Node; - BOOST_FOREACH(const Key_Node& key_node, keys) { stack2.push(key_node.second); } + for(const Key_Node& key_node: keys) { stack2.push(key_node.second); } } } diff --git a/gtsam/inference/Factor.cpp b/gtsam/inference/Factor.cpp index 707193a52..49f34fb2b 100644 --- a/gtsam/inference/Factor.cpp +++ b/gtsam/inference/Factor.cpp @@ -19,7 +19,6 @@ // \callgraph -#include #include #include @@ -35,7 +34,7 @@ namespace gtsam { /* ************************************************************************* */ void Factor::printKeys(const std::string& s, const KeyFormatter& formatter) const { std::cout << s << " "; - BOOST_FOREACH(Key key, keys_) std::cout << " " << formatter(key); + for(Key key: keys_) std::cout << " " << formatter(key); std::cout << std::endl; } @@ -44,4 +43,4 @@ namespace gtsam { return keys_ == other.keys_; } -} \ No newline at end of file +} diff --git a/gtsam/inference/ISAM-inst.h b/gtsam/inference/ISAM-inst.h index 99f668591..bf2cacc84 100644 --- a/gtsam/inference/ISAM-inst.h +++ b/gtsam/inference/ISAM-inst.h @@ -39,7 +39,7 @@ namespace gtsam { factors += newFactors; // Add the orphaned subtrees - BOOST_FOREACH(const sharedClique& orphan, orphans) + for(const sharedClique& orphan: orphans) factors += boost::make_shared >(orphan); // eliminate into a Bayes net diff --git a/gtsam/inference/JunctionTree-inst.h b/gtsam/inference/JunctionTree-inst.h index 352a8dded..8fcdd1eac 100644 --- a/gtsam/inference/JunctionTree-inst.h +++ b/gtsam/inference/JunctionTree-inst.h @@ -105,7 +105,7 @@ struct ConstructorTraversalData { // decide which children to merge, as index into children std::vector merge(nrChildren, false); size_t myNrFrontals = 1, i = 0; - BOOST_FOREACH(const sharedNode& child, node->children) { + for(const sharedNode& child: node->children) { // Check if we should merge the i^th child if (myNrParents + myNrFrontals == childConditionals[i]->nrParents()) { // Increment number of frontal variables diff --git a/gtsam/inference/Key.cpp b/gtsam/inference/Key.cpp index a2a6906d1..f25727441 100644 --- a/gtsam/inference/Key.cpp +++ b/gtsam/inference/Key.cpp @@ -20,7 +20,6 @@ #include #include -#include #include #include @@ -63,7 +62,7 @@ static void Print(const CONTAINER& keys, const string& s, if (keys.empty()) cout << "(none)" << endl; else { - BOOST_FOREACH(const Key& key, keys) + for(const Key& key: keys) cout << keyFormatter(key) << " "; cout << endl; } diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 06e5ddeec..eb9670254 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -17,7 +17,6 @@ #pragma once -#include #include #include @@ -42,7 +41,7 @@ void MetisIndex::augment(const FactorGraph& factors) { // key to integer mapping. This is referenced during the adjaceny step for (size_t i = 0; i < factors.size(); i++) { if (factors[i]) { - BOOST_FOREACH(const Key& key, *factors[i]) { + for(const Key& key: *factors[i]) { keySet.insert(keySet.end(), key); // Keep a track of all unique keys if (intKeyBMap_.left.find(key) == intKeyBMap_.left.end()) { intKeyBMap_.insert(bm_type::value_type(key, keyCounter)); @@ -55,8 +54,8 @@ void MetisIndex::augment(const FactorGraph& factors) { // Create an adjacency mapping that stores the set of all adjacent keys for every key for (size_t i = 0; i < factors.size(); i++) { if (factors[i]) { - BOOST_FOREACH(const Key& k1, *factors[i]) - BOOST_FOREACH(const Key& k2, *factors[i]) + for(const Key& k1: *factors[i]) + for(const Key& k2: *factors[i]) if (k1 != k2) { // Store both in Key and int32_t format int i = intKeyBMap_.left.at(k1); diff --git a/gtsam/inference/VariableIndex-inl.h b/gtsam/inference/VariableIndex-inl.h index c00a3633e..b9f143a0f 100644 --- a/gtsam/inference/VariableIndex-inl.h +++ b/gtsam/inference/VariableIndex-inl.h @@ -34,7 +34,7 @@ void VariableIndex::augment(const FG& factors, if (factors[i]) { const size_t globalI = newFactorIndices ? (*newFactorIndices)[i] : nFactors_; - BOOST_FOREACH(const Key key, *factors[i]) { + for(const Key key: *factors[i]) { index_[key].push_back(globalI); ++nEntries_; } @@ -67,7 +67,7 @@ void VariableIndex::remove(ITERATOR firstFactor, ITERATOR lastFactor, throw std::invalid_argument( "Internal error, requested inconsistent number of factor indices and factors in VariableIndex::remove"); if (factors[i]) { - BOOST_FOREACH(Key j, *factors[i]) { + for(Key j: *factors[i]) { Factors& factorEntries = internalAt(j); Factors::iterator entry = std::find(factorEntries.begin(), factorEntries.end(), *factorIndex); diff --git a/gtsam/inference/VariableIndex.cpp b/gtsam/inference/VariableIndex.cpp index e67c0e248..72c56be5b 100644 --- a/gtsam/inference/VariableIndex.cpp +++ b/gtsam/inference/VariableIndex.cpp @@ -33,9 +33,9 @@ bool VariableIndex::equals(const VariableIndex& other, double tol) const { void VariableIndex::print(const string& str, const KeyFormatter& keyFormatter) const { cout << str; cout << "nEntries = " << nEntries() << ", nFactors = " << nFactors() << "\n"; - BOOST_FOREACH(KeyMap::value_type key_factors, index_) { + for(KeyMap::value_type key_factors: index_) { cout << "var " << keyFormatter(key_factors.first) << ":"; - BOOST_FOREACH(const size_t factor, key_factors.second) + for(const size_t factor: key_factors.second) cout << " " << factor; cout << "\n"; } @@ -46,9 +46,9 @@ void VariableIndex::print(const string& str, const KeyFormatter& keyFormatter) c void VariableIndex::outputMetisFormat(ostream& os) const { os << size() << " " << nFactors() << "\n"; // run over variables, which will be hyper-edges. - BOOST_FOREACH(KeyMap::value_type key_factors, index_) { + for(KeyMap::value_type key_factors: index_) { // every variable is a hyper-edge covering its factors - BOOST_FOREACH(const size_t factor, key_factors.second) + for(const size_t factor: key_factors.second) os << (factor+1) << " "; // base 1 os << "\n"; } diff --git a/gtsam/inference/VariableSlots.cpp b/gtsam/inference/VariableSlots.cpp index 783071ae2..d89ad2ced 100644 --- a/gtsam/inference/VariableSlots.cpp +++ b/gtsam/inference/VariableSlots.cpp @@ -18,7 +18,6 @@ #include #include -#include using namespace std; @@ -33,12 +32,12 @@ void VariableSlots::print(const std::string& str) const { else { cout << str << "\n"; cout << "Var:\t"; - BOOST_FOREACH(const value_type& slot, *this) { cout << slot.first << "\t"; } + for(const value_type& slot: *this) { cout << slot.first << "\t"; } cout << "\n"; for(size_t i=0; ibegin()->second.size(); ++i) { cout << " \t"; - BOOST_FOREACH(const value_type& slot, *this) { + for(const value_type& slot: *this) { if(slot.second[i] == Empty) cout << "x" << "\t"; else diff --git a/gtsam/inference/VariableSlots.h b/gtsam/inference/VariableSlots.h index fad789436..8ebd5c13c 100644 --- a/gtsam/inference/VariableSlots.h +++ b/gtsam/inference/VariableSlots.h @@ -24,7 +24,6 @@ #include #include -#include #include #include @@ -99,10 +98,10 @@ VariableSlots::VariableSlots(const FG& factorGraph) // removed factors. The slot number is the max integer value if the // factor does not involve that variable. size_t jointFactorPos = 0; - BOOST_FOREACH(const typename FG::sharedFactor& factor, factorGraph) { + for(const typename FG::sharedFactor& factor: factorGraph) { assert(factor); size_t factorVarSlot = 0; - BOOST_FOREACH(const Key involvedVariable, *factor) { + for(const Key involvedVariable: *factor) { // Set the slot in this factor for this variable. If the // variable was not already discovered, create an array for it // that we'll fill with the slot indices for each factor that