diff --git a/examples/VisualSLAMData.h b/examples/VisualSLAMData.h index 1a55e1a26..b96c24295 100644 --- a/examples/VisualSLAMData.h +++ b/examples/VisualSLAMData.h @@ -41,7 +41,7 @@ struct VisualSLAMExampleData { std::vector poses; // ground-truth camera poses gtsam::Pose3 odometry; // ground-truth odometry between 2 consecutive poses (simulated data for iSAM) std::vector points; // ground-truth landmarks - std::map > z; // 2D measurements of landmarks in each camera frame + std::map > z; // 2D measurements of landmarks in each camera frame gtsam::SharedDiagonal noiseZ; // measurement noise (noiseModel::Isotropic::Sigma(2, 5.0f)); gtsam::SharedDiagonal noiseX; // noise for camera poses gtsam::SharedDiagonal noiseL; // noise for landmarks diff --git a/gtsam/inference/ClusterTree-inl.h b/gtsam/inference/ClusterTree-inl.h index 267602eea..548a55cf4 100644 --- a/gtsam/inference/ClusterTree-inl.h +++ b/gtsam/inference/ClusterTree-inl.h @@ -61,8 +61,8 @@ namespace gtsam { if (separator != other.separator) return false; if (children_.size() != other.children_.size()) return false; - typename list::const_iterator it1 = children_.begin(); - typename list::const_iterator it2 = other.children_.begin(); + typename std::list::const_iterator it1 = children_.begin(); + typename std::list::const_iterator it2 = other.children_.begin(); for (; it1 != children_.end(); it1++, it2++) if (!(*it1)->equals(**it2)) return false; diff --git a/gtsam/inference/graph-inl.h b/gtsam/inference/graph-inl.h index b086fd2fb..195e18d73 100644 --- a/gtsam/inference/graph-inl.h +++ b/gtsam/inference/graph-inl.h @@ -42,7 +42,7 @@ public: /* ************************************************************************* */ template -list predecessorMap2Keys(const PredecessorMap& p_map) { +std::list predecessorMap2Keys(const PredecessorMap& p_map) { typedef typename SGraph::Vertex SVertex; @@ -102,7 +102,7 @@ SDGraph toBoostGraph(const G& graph) { /* ************************************************************************* */ template -boost::tuple > +boost::tuple > predecessorMap2Graph(const PredecessorMap& p_map) { G g; diff --git a/gtsam/inference/tests/testBayesTree.cpp b/gtsam/inference/tests/testBayesTree.cpp index 71021ef70..2f85e1454 100644 --- a/gtsam/inference/tests/testBayesTree.cpp +++ b/gtsam/inference/tests/testBayesTree.cpp @@ -30,6 +30,7 @@ using namespace boost::assign; #include #include +using namespace std; using namespace gtsam; typedef BayesTree SymbolicBayesTree; diff --git a/gtsam/inference/tests/testVariableIndex.cpp b/gtsam/inference/tests/testVariableIndex.cpp index a990a5a87..7c8e6fa9e 100644 --- a/gtsam/inference/tests/testVariableIndex.cpp +++ b/gtsam/inference/tests/testVariableIndex.cpp @@ -22,6 +22,7 @@ #include #include +using namespace std; using namespace gtsam; /* ************************************************************************* */ diff --git a/gtsam/linear/SimpleSPCGSolver.cpp b/gtsam/linear/SimpleSPCGSolver.cpp index 8f59b9058..b08cc0c36 100644 --- a/gtsam/linear/SimpleSPCGSolver.cpp +++ b/gtsam/linear/SimpleSPCGSolver.cpp @@ -97,13 +97,13 @@ VectorValues::shared_ptr SimpleSPCGSolver::optimize (const VectorValues &initial double gamma = s.vector().squaredNorm(), new_gamma = 0.0, alpha = 0.0, beta = 0.0 ; const double threshold = - ::max(parameters_.epsilon_abs(), + std::max(parameters_.epsilon_abs(), parameters_.epsilon() * parameters_.epsilon() * gamma); const size_t iMaxIterations = parameters_.maxIterations(); const ConjugateGradientParameters::Verbosity verbosity = parameters_.cg_.verbosity(); if ( verbosity >= ConjugateGradientParameters::ERROR ) - cout << "[SimpleSPCGSolver] epsilon = " << parameters_.epsilon() + std::cout << "[SimpleSPCGSolver] epsilon = " << parameters_.epsilon() << ", max = " << parameters_.maxIterations() << ", ||r0|| = " << std::sqrt(gamma) << ", threshold = " << threshold << std::endl; @@ -122,14 +122,14 @@ VectorValues::shared_ptr SimpleSPCGSolver::optimize (const VectorValues &initial gamma = new_gamma ; if ( verbosity >= ConjugateGradientParameters::ERROR) { - cout << "[SimpleSPCGSolver] iteration " << k << ": a = " << alpha << ": b = " << beta << ", ||r|| = " << std::sqrt(gamma) << endl; + std::cout << "[SimpleSPCGSolver] iteration " << k << ": a = " << alpha << ": b = " << beta << ", ||r|| = " << std::sqrt(gamma) << std::endl; } if ( gamma < threshold ) break ; } // k if ( verbosity >= ConjugateGradientParameters::ERROR ) - cout << "[SimpleSPCGSolver] iteration " << k << ": a = " << alpha << ": b = " << beta << ", ||r|| = " << std::sqrt(gamma) << endl; + std::cout << "[SimpleSPCGSolver] iteration " << k << ": a = " << alpha << ": b = " << beta << ", ||r|| = " << std::sqrt(gamma) << std::endl; /* transform y back to x */ return this->transform(*x); diff --git a/gtsam/nonlinear/DoglegOptimizerImpl.cpp b/gtsam/nonlinear/DoglegOptimizerImpl.cpp index ccfdf781a..b46fc6a3f 100644 --- a/gtsam/nonlinear/DoglegOptimizerImpl.cpp +++ b/gtsam/nonlinear/DoglegOptimizerImpl.cpp @@ -18,6 +18,8 @@ #include #include +using namespace std; + namespace gtsam { /* ************************************************************************* */ VectorValues DoglegOptimizerImpl::ComputeDoglegPoint( diff --git a/gtsam/nonlinear/Marginals.cpp b/gtsam/nonlinear/Marginals.cpp index 936cfb806..da3632570 100644 --- a/gtsam/nonlinear/Marginals.cpp +++ b/gtsam/nonlinear/Marginals.cpp @@ -21,6 +21,8 @@ #include #include +using namespace std; + namespace gtsam { /* ************************************************************************* */ diff --git a/gtsam_unstable/discrete/CSP.cpp b/gtsam_unstable/discrete/CSP.cpp index 4a041c9b2..20c0e7617 100644 --- a/gtsam_unstable/discrete/CSP.cpp +++ b/gtsam_unstable/discrete/CSP.cpp @@ -11,6 +11,8 @@ #include #include +using namespace std; + namespace gtsam { /// Find the best total assignment - can be expensive diff --git a/gtsam_unstable/discrete/tests/testCSP.cpp b/gtsam_unstable/discrete/tests/testCSP.cpp index c92cbe1f9..4ab5cd361 100644 --- a/gtsam_unstable/discrete/tests/testCSP.cpp +++ b/gtsam_unstable/discrete/tests/testCSP.cpp @@ -7,6 +7,8 @@ #include #include +#include +using boost::assign::insert; #include #include #include diff --git a/gtsam_unstable/discrete/tests/testSudoku.cpp b/gtsam_unstable/discrete/tests/testSudoku.cpp index a32ca2645..1e4026e7f 100644 --- a/gtsam_unstable/discrete/tests/testSudoku.cpp +++ b/gtsam_unstable/discrete/tests/testSudoku.cpp @@ -7,6 +7,8 @@ #include #include +#include +using boost::assign::insert; #include #include #include diff --git a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp index 1749ded1a..916d07559 100644 --- a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp +++ b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp @@ -7,6 +7,7 @@ #include +using namespace std; using namespace gtsam; using namespace imu;