Removed using namespace in header files
parent
30fd9d2a95
commit
a23127a315
|
@ -27,6 +27,7 @@
|
|||
#include <boost/foreach.hpp>
|
||||
#include <boost/tuple/tuple.hpp>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
using boost::assign::operator+=;
|
||||
#include <boost/unordered_set.hpp>
|
||||
#include <boost/noncopyable.hpp>
|
||||
|
||||
|
@ -37,8 +38,6 @@
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
using namespace boost::assign;
|
||||
|
||||
/*********************************************************************************/
|
||||
// Node
|
||||
/*********************************************************************************/
|
||||
|
|
|
@ -66,7 +66,7 @@ namespace gtsam {
|
|||
Index j = (key);
|
||||
size_t value = parentsValues.at(j);
|
||||
pFS = pFS.choose(j, value);
|
||||
} catch (exception& e) {
|
||||
} catch (exception&) {
|
||||
throw runtime_error(
|
||||
"DiscreteConditional::choose: parent value missing");
|
||||
};
|
||||
|
|
|
@ -64,7 +64,7 @@ namespace gtsam {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
pair<DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr> //
|
||||
std::pair<DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr> //
|
||||
EliminateDiscrete(const FactorGraph<DiscreteFactor>& factors, size_t num) {
|
||||
|
||||
// PRODUCT: multiply all factors
|
||||
|
@ -87,7 +87,7 @@ namespace gtsam {
|
|||
toc(3, "divide");
|
||||
tictoc_finishedIteration();
|
||||
|
||||
return make_pair(cond, sum);
|
||||
return std::make_pair(cond, sum);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -24,20 +24,20 @@
|
|||
#include <boost/format.hpp>
|
||||
|
||||
#include <boost/assign/std/vector.hpp> // for +=
|
||||
using namespace boost::assign;
|
||||
using boost::assign::operator+=;
|
||||
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class CONDITIONAL>
|
||||
void BayesNet<CONDITIONAL>::print(const std::string& s) const {
|
||||
std::cout << s;
|
||||
BOOST_REVERSE_FOREACH(sharedConditional conditional,conditionals_)
|
||||
conditional->print();
|
||||
}
|
||||
/* ************************************************************************* */
|
||||
template<class CONDITIONAL>
|
||||
void BayesNet<CONDITIONAL>::print(const std::string& s) const {
|
||||
std::cout << s;
|
||||
BOOST_REVERSE_FOREACH(sharedConditional conditional, conditionals_)
|
||||
conditional->print();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class CONDITIONAL>
|
||||
|
|
|
@ -26,14 +26,17 @@
|
|||
#include <gtsam/inference/inference.h>
|
||||
#include <gtsam/inference/GenericSequentialSolver.h>
|
||||
|
||||
#include <boost/foreach.hpp>
|
||||
#include <boost/assign/std/list.hpp> // for operator +=
|
||||
#include <boost/format.hpp>
|
||||
|
||||
#include <fstream>
|
||||
#include <iostream>
|
||||
#include <algorithm>
|
||||
|
||||
#include <boost/foreach.hpp>
|
||||
#include <boost/assign/std/list.hpp> // for operator +=
|
||||
using boost::assign::operator+=;
|
||||
#include <boost/format.hpp>
|
||||
|
||||
namespace lam = boost::lambda;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -328,7 +331,7 @@ namespace gtsam {
|
|||
printf("WARNING: BayesTree.print encountered a forest...\n");
|
||||
return;
|
||||
}
|
||||
std::cout << s << ": clique size == " << size() << ", node size == " << nodes_.size() << std::endl;
|
||||
std::cout << s << ": clique size == " << size() << ", node size == " << nodes_.size() << std::endl;
|
||||
if (nodes_.empty()) return;
|
||||
root_->printTree("");
|
||||
}
|
||||
|
|
|
@ -26,8 +26,6 @@
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
using namespace std;
|
||||
|
||||
/* ************************************************************************* *
|
||||
* Cluster
|
||||
* ************************************************************************* */
|
||||
|
@ -73,19 +71,19 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FG>
|
||||
void ClusterTree<FG>::Cluster::print(const string& indent) const {
|
||||
cout << indent;
|
||||
void ClusterTree<FG>::Cluster::print(const std::string& indent) const {
|
||||
std::cout << indent;
|
||||
BOOST_FOREACH(const Index key, frontal)
|
||||
cout << key << " ";
|
||||
cout << ": ";
|
||||
std::cout << key << " ";
|
||||
std::cout << ": ";
|
||||
BOOST_FOREACH(const Index key, separator)
|
||||
cout << key << " ";
|
||||
cout << endl;
|
||||
std::cout << key << " ";
|
||||
std::cout << std::endl;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class FG>
|
||||
void ClusterTree<FG>::Cluster::printTree(const string& indent) const {
|
||||
void ClusterTree<FG>::Cluster::printTree(const std::string& indent) const {
|
||||
print(indent);
|
||||
BOOST_FOREACH(const shared_ptr& child, children_)
|
||||
child->printTree(indent + " ");
|
||||
|
@ -95,8 +93,8 @@ namespace gtsam {
|
|||
* ClusterTree
|
||||
* ************************************************************************* */
|
||||
template<class FG>
|
||||
void ClusterTree<FG>::print(const string& str) const {
|
||||
cout << str << endl;
|
||||
void ClusterTree<FG>::print(const std::string& str) const {
|
||||
std::cout << str << std::endl;
|
||||
if (root_) root_->printTree("");
|
||||
}
|
||||
|
||||
|
|
|
@ -34,17 +34,15 @@
|
|||
#include <sstream>
|
||||
#include <stdexcept>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTOR>
|
||||
void FactorGraph<FACTOR>::print(const string& s) const {
|
||||
cout << s << endl;
|
||||
cout << "size: " << size() << endl;
|
||||
void FactorGraph<FACTOR>::print(const std::string& s) const {
|
||||
std::cout << s << std::endl;
|
||||
std::cout << "size: " << size() << std::endl;
|
||||
for (size_t i = 0; i < factors_.size(); i++) {
|
||||
stringstream ss;
|
||||
std::stringstream ss;
|
||||
ss << "factor " << i << ": ";
|
||||
if (factors_[i] != NULL) factors_[i]->print(ss.str());
|
||||
}
|
||||
|
@ -79,7 +77,7 @@ namespace gtsam {
|
|||
/* ************************************************************************* */
|
||||
template<class FACTOR>
|
||||
void FactorGraph<FACTOR>::replace(size_t index, sharedFactor factor) {
|
||||
if (index >= factors_.size()) throw invalid_argument(boost::str(
|
||||
if (index >= factors_.size()) throw std::invalid_argument(boost::str(
|
||||
boost::format("Factor graph does not contain a factor with index %d.")
|
||||
% index));
|
||||
// Replace the factor
|
||||
|
@ -115,7 +113,7 @@ namespace gtsam {
|
|||
/* ************************************************************************* */
|
||||
template<class FACTOR, class CONDITIONAL, class CLIQUE>
|
||||
void _FactorGraph_BayesTree_adder(
|
||||
vector<typename FactorGraph<FACTOR>::sharedFactor>& factors,
|
||||
std::vector<typename FactorGraph<FACTOR>::sharedFactor>& factors,
|
||||
const typename BayesTree<CONDITIONAL,CLIQUE>::sharedClique& clique) {
|
||||
|
||||
if(clique) {
|
||||
|
|
|
@ -21,8 +21,6 @@
|
|||
#include <gtsam/inference/JunctionTree.h>
|
||||
#include <gtsam/inference/BayesNet-inl.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -69,7 +67,7 @@ namespace gtsam {
|
|||
|
||||
// We currently have code written only for computing the
|
||||
|
||||
if (js.size() != 2) throw domain_error(
|
||||
if (js.size() != 2) throw std::domain_error(
|
||||
"*MultifrontalSolver::joint(js) currently can only compute joint marginals\n"
|
||||
"for exactly two variables. You can call marginal to compute the\n"
|
||||
"marginal for one variable. *SequentialSolver::joint(js) can compute the\n"
|
||||
|
|
|
@ -19,7 +19,6 @@
|
|||
|
||||
#include <boost/foreach.hpp>
|
||||
#include <boost/assign/std/list.hpp> // for operator +=
|
||||
using namespace boost::assign;
|
||||
|
||||
#include <gtsam/inference/Conditional.h>
|
||||
#include <gtsam/inference/BayesTree.h>
|
||||
|
@ -27,8 +26,6 @@ using namespace boost::assign;
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
using namespace std;
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class CONDITIONAL>
|
||||
ISAM<CONDITIONAL>::ISAM() : BayesTree<CONDITIONAL>() {}
|
||||
|
|
|
@ -79,7 +79,7 @@ namespace gtsam {
|
|||
|
||||
// Two stages - first build an array of the lowest-ordered variable in each
|
||||
// factor and find the last variable to be eliminated.
|
||||
vector<Index> lowestOrdered(fg.size(), numeric_limits<Index>::max());
|
||||
std::vector<Index> lowestOrdered(fg.size(), std::numeric_limits<Index>::max());
|
||||
Index maxVar = 0;
|
||||
for(size_t i=0; i<fg.size(); ++i)
|
||||
if(fg[i]) {
|
||||
|
@ -92,9 +92,9 @@ namespace gtsam {
|
|||
|
||||
// Now add each factor to the list corresponding to its lowest-ordered
|
||||
// variable.
|
||||
vector<FastList<size_t> > targets(maxVar+1);
|
||||
std::vector<FastList<size_t> > targets(maxVar+1);
|
||||
for(size_t i=0; i<lowestOrdered.size(); ++i)
|
||||
if(lowestOrdered[i] != numeric_limits<Index>::max())
|
||||
if(lowestOrdered[i] != std::numeric_limits<Index>::max())
|
||||
targets[lowestOrdered[i]].push_back(i);
|
||||
|
||||
// Now call the recursive distributeFactors
|
||||
|
@ -141,7 +141,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class FG, class BTCLIQUE>
|
||||
pair<typename JunctionTree<FG,BTCLIQUE>::BTClique::shared_ptr,
|
||||
std::pair<typename JunctionTree<FG,BTCLIQUE>::BTClique::shared_ptr,
|
||||
typename FG::sharedFactor> JunctionTree<FG,BTCLIQUE>::eliminateOneClique(
|
||||
typename FG::Eliminate function,
|
||||
const boost::shared_ptr<const Clique>& current) const {
|
||||
|
@ -151,9 +151,9 @@ namespace gtsam {
|
|||
fg.push_back(*current); // add the local factors
|
||||
|
||||
// receive the factors from the child and its clique point
|
||||
list<typename BTClique::shared_ptr> children;
|
||||
std::list<typename BTClique::shared_ptr> children;
|
||||
BOOST_FOREACH(const boost::shared_ptr<const Clique>& child, current->children()) {
|
||||
pair<typename BTClique::shared_ptr, typename FG::sharedFactor> tree_factor(
|
||||
std::pair<typename BTClique::shared_ptr, typename FG::sharedFactor> tree_factor(
|
||||
eliminateOneClique(function, child));
|
||||
children.push_back(tree_factor.first);
|
||||
fg.push_back(tree_factor.second);
|
||||
|
@ -181,7 +181,7 @@ namespace gtsam {
|
|||
}
|
||||
toc(3, "Update tree");
|
||||
|
||||
return make_pair(new_clique, eliminated.second);
|
||||
return std::make_pair(new_clique, eliminated.second);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -190,9 +190,9 @@ namespace gtsam {
|
|||
typename FG::Eliminate function) const {
|
||||
if (this->root()) {
|
||||
tic(2, "JT eliminate");
|
||||
pair<typename BTClique::shared_ptr, typename FG::sharedFactor> ret =
|
||||
std::pair<typename BTClique::shared_ptr, typename FG::sharedFactor> ret =
|
||||
this->eliminateOneClique(function, this->root());
|
||||
if (ret.second->size() != 0) throw runtime_error(
|
||||
if (ret.second->size() != 0) throw std::runtime_error(
|
||||
"JuntionTree::eliminate: elimination failed because of factors left over!");
|
||||
toc(2, "JT eliminate");
|
||||
return ret.first;
|
||||
|
|
|
@ -24,8 +24,6 @@
|
|||
|
||||
#include <gtsam/inference/graph.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
#define FOREACH_PAIR( KEY, VAL, COL) BOOST_FOREACH (boost::tie(KEY,VAL),COL)
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -66,7 +64,7 @@ SDGraph<KEY> toBoostGraph(const G& graph) {
|
|||
// convert the factor graph to boost graph
|
||||
SDGraph<KEY> g;
|
||||
typedef typename boost::graph_traits<SDGraph<KEY> >::vertex_descriptor BoostVertex;
|
||||
map<KEY, BoostVertex> key2vertex;
|
||||
std::map<KEY, BoostVertex> key2vertex;
|
||||
BoostVertex v1, v2;
|
||||
typename G::const_iterator itFactor;
|
||||
|
||||
|
@ -108,7 +106,7 @@ boost::tuple<G, V, map<KEY,V> >
|
|||
predecessorMap2Graph(const PredecessorMap<KEY>& p_map) {
|
||||
|
||||
G g;
|
||||
map<KEY, V> key2vertex;
|
||||
std::map<KEY, V> key2vertex;
|
||||
V v1, v2, root;
|
||||
KEY child, parent;
|
||||
bool foundRoot = false;
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
#include <boost/range/adaptors.hpp>
|
||||
#include <boost/range/algorithm.hpp>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -22,8 +22,6 @@
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
using namespace std;
|
||||
|
||||
struct ISAM2::Impl {
|
||||
|
||||
struct PartialSolveResult {
|
||||
|
@ -49,7 +47,7 @@ struct ISAM2::Impl {
|
|||
* @param keyFormatter Formatter for printing nonlinear keys during debugging
|
||||
*/
|
||||
static void AddVariables(const Values& newTheta, Values& theta, Permuted<VectorValues>& delta,
|
||||
Permuted<VectorValues>& deltaNewton, Permuted<VectorValues>& deltaGradSearch, vector<bool>& replacedKeys,
|
||||
Permuted<VectorValues>& deltaNewton, Permuted<VectorValues>& deltaGradSearch, std::vector<bool>& replacedKeys,
|
||||
Ordering& ordering, Base::Nodes& nodes, const KeyFormatter& keyFormatter = DefaultKeyFormatter);
|
||||
|
||||
/**
|
||||
|
@ -88,7 +86,7 @@ struct ISAM2::Impl {
|
|||
*
|
||||
* Alternatively could we trace up towards the root for each variable here?
|
||||
*/
|
||||
static void FindAll(ISAM2Clique::shared_ptr clique, FastSet<Index>& keys, const vector<bool>& markedMask);
|
||||
static void FindAll(ISAM2Clique::shared_ptr clique, FastSet<Index>& keys, const std::vector<bool>& markedMask);
|
||||
|
||||
/**
|
||||
* Apply expmap to the given values, but only for indices appearing in
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
using namespace std;
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class VALUE>
|
||||
VALUE ISAM2::calculateEstimate(Key key) const {
|
||||
|
@ -39,7 +37,7 @@ VALUE ISAM2::calculateEstimate(Key key) const {
|
|||
namespace internal {
|
||||
template<class CLIQUE>
|
||||
void optimizeWildfire(const boost::shared_ptr<CLIQUE>& clique, double threshold,
|
||||
vector<bool>& changed, const vector<bool>& replaced, Permuted<VectorValues>& delta, int& count) {
|
||||
std::vector<bool>& changed, const std::vector<bool>& replaced, Permuted<VectorValues>& delta, int& count) {
|
||||
// if none of the variables in this clique (frontal and separator!) changed
|
||||
// significantly, then by the running intersection property, none of the
|
||||
// cliques in the children need to be processed
|
||||
|
@ -68,7 +66,7 @@ void optimizeWildfire(const boost::shared_ptr<CLIQUE>& clique, double threshold,
|
|||
if(recalculate) {
|
||||
|
||||
// Temporary copy of the original values, to check how much they change
|
||||
vector<Vector> originalValues((*clique)->nrFrontals());
|
||||
std::vector<Vector> originalValues((*clique)->nrFrontals());
|
||||
GaussianConditional::const_iterator it;
|
||||
for(it = (*clique)->beginFrontals(); it!=(*clique)->endFrontals(); it++) {
|
||||
originalValues[it - (*clique)->beginFrontals()] = delta[*it];
|
||||
|
@ -116,8 +114,8 @@ void optimizeWildfire(const boost::shared_ptr<CLIQUE>& clique, double threshold,
|
|||
|
||||
/* ************************************************************************* */
|
||||
template<class CLIQUE>
|
||||
int optimizeWildfire(const boost::shared_ptr<CLIQUE>& root, double threshold, const vector<bool>& keys, Permuted<VectorValues>& delta) {
|
||||
vector<bool> changed(keys.size(), false);
|
||||
int optimizeWildfire(const boost::shared_ptr<CLIQUE>& root, double threshold, const std::vector<bool>& keys, Permuted<VectorValues>& delta) {
|
||||
std::vector<bool> changed(keys.size(), false);
|
||||
int count = 0;
|
||||
// starting from the root, call optimize on each conditional
|
||||
if(root)
|
||||
|
|
|
@ -246,7 +246,7 @@ struct ISAM2Clique : public BayesTreeCliqueBase<ISAM2Clique, GaussianConditional
|
|||
|
||||
/** Construct from a conditional */
|
||||
ISAM2Clique(const sharedConditional& conditional) : Base(conditional) {
|
||||
throw runtime_error("ISAM2Clique should always be constructed with the elimination result constructor"); }
|
||||
throw std::runtime_error("ISAM2Clique should always be constructed with the elimination result constructor"); }
|
||||
|
||||
/** Construct from an elimination result */
|
||||
ISAM2Clique(const std::pair<sharedConditional, boost::shared_ptr<ConditionalType::FactorType> >& result) :
|
||||
|
@ -260,7 +260,7 @@ struct ISAM2Clique : public BayesTreeCliqueBase<ISAM2Clique, GaussianConditional
|
|||
|
||||
/** Produce a deep copy, copying the cached factor and gradient contribution */
|
||||
shared_ptr clone() const {
|
||||
shared_ptr copy(new ISAM2Clique(make_pair(
|
||||
shared_ptr copy(new ISAM2Clique(std::make_pair(
|
||||
sharedConditional(new ConditionalType(*Base::conditional_)),
|
||||
cachedFactor_ ? cachedFactor_->clone() : Base::FactorType::shared_ptr())));
|
||||
copy->gradientContribution_ = gradientContribution_;
|
||||
|
@ -283,7 +283,7 @@ struct ISAM2Clique : public BayesTreeCliqueBase<ISAM2Clique, GaussianConditional
|
|||
if(cachedFactor_)
|
||||
cachedFactor_->print(s + "Cached: ");
|
||||
else
|
||||
cout << s << "Cached empty" << endl;
|
||||
std::cout << s << "Cached empty" << std::endl;
|
||||
if(gradientContribution_.rows() != 0)
|
||||
gtsam::print(gradientContribution_, "Gradient contribution: ");
|
||||
}
|
||||
|
|
|
@ -100,7 +100,7 @@ public:
|
|||
virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
|
||||
std::cout << s << "keys = { ";
|
||||
BOOST_FOREACH(Key key, this->keys()) { std::cout << keyFormatter(key) << " "; }
|
||||
std::cout << "}" << endl;
|
||||
std::cout << "}" << std::endl;
|
||||
}
|
||||
|
||||
/** Check if two factors are equal */
|
||||
|
|
|
@ -104,7 +104,7 @@ public:
|
|||
return EliminateQR;
|
||||
|
||||
default:
|
||||
throw runtime_error("Nonlinear optimization parameter \"factorization\" is invalid");
|
||||
throw std::runtime_error("Nonlinear optimization parameter \"factorization\" is invalid");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -97,8 +97,8 @@ namespace gtsam {
|
|||
} catch( CheiralityException& e) {
|
||||
if (H1) *H1 = zeros(2,6);
|
||||
if (H2) *H2 = zeros(2,3);
|
||||
cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
|
||||
" moved behind camera " << DefaultKeyFormatter(this->key1()) << endl;
|
||||
std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
|
||||
" moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl;
|
||||
return ones(2) * 2.0 * K_->fx();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -22,8 +22,6 @@
|
|||
#include <gtsam/linear/IterativeOptimizationParameters.h>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
Loading…
Reference in New Issue