Removed using namespace in header files

release/4.3a0
Richard Roberts 2012-06-08 14:33:59 +00:00
parent dd79bacfab
commit d188ed2e1a
12 changed files with 22 additions and 9 deletions

View File

@ -41,7 +41,7 @@ struct VisualSLAMExampleData {
std::vector<gtsam::Pose3> poses; // ground-truth camera poses std::vector<gtsam::Pose3> poses; // ground-truth camera poses
gtsam::Pose3 odometry; // ground-truth odometry between 2 consecutive poses (simulated data for iSAM) gtsam::Pose3 odometry; // ground-truth odometry between 2 consecutive poses (simulated data for iSAM)
std::vector<gtsam::Point3> points; // ground-truth landmarks std::vector<gtsam::Point3> points; // ground-truth landmarks
std::map<int, vector<gtsam::Point2> > z; // 2D measurements of landmarks in each camera frame std::map<int, std::vector<gtsam::Point2> > z; // 2D measurements of landmarks in each camera frame
gtsam::SharedDiagonal noiseZ; // measurement noise (noiseModel::Isotropic::Sigma(2, 5.0f)); gtsam::SharedDiagonal noiseZ; // measurement noise (noiseModel::Isotropic::Sigma(2, 5.0f));
gtsam::SharedDiagonal noiseX; // noise for camera poses gtsam::SharedDiagonal noiseX; // noise for camera poses
gtsam::SharedDiagonal noiseL; // noise for landmarks gtsam::SharedDiagonal noiseL; // noise for landmarks

View File

@ -61,8 +61,8 @@ namespace gtsam {
if (separator != other.separator) return false; if (separator != other.separator) return false;
if (children_.size() != other.children_.size()) return false; if (children_.size() != other.children_.size()) return false;
typename list<shared_ptr>::const_iterator it1 = children_.begin(); typename std::list<shared_ptr>::const_iterator it1 = children_.begin();
typename list<shared_ptr>::const_iterator it2 = other.children_.begin(); typename std::list<shared_ptr>::const_iterator it2 = other.children_.begin();
for (; it1 != children_.end(); it1++, it2++) for (; it1 != children_.end(); it1++, it2++)
if (!(*it1)->equals(**it2)) return false; if (!(*it1)->equals(**it2)) return false;

View File

@ -42,7 +42,7 @@ public:
/* ************************************************************************* */ /* ************************************************************************* */
template<class KEY> template<class KEY>
list<KEY> predecessorMap2Keys(const PredecessorMap<KEY>& p_map) { std::list<KEY> predecessorMap2Keys(const PredecessorMap<KEY>& p_map) {
typedef typename SGraph<KEY>::Vertex SVertex; typedef typename SGraph<KEY>::Vertex SVertex;
@ -102,7 +102,7 @@ SDGraph<KEY> toBoostGraph(const G& graph) {
/* ************************************************************************* */ /* ************************************************************************* */
template<class G, class V, class KEY> template<class G, class V, class KEY>
boost::tuple<G, V, map<KEY,V> > boost::tuple<G, V, std::map<KEY,V> >
predecessorMap2Graph(const PredecessorMap<KEY>& p_map) { predecessorMap2Graph(const PredecessorMap<KEY>& p_map) {
G g; G g;

View File

@ -30,6 +30,7 @@ using namespace boost::assign;
#include <gtsam/inference/IndexFactor.h> #include <gtsam/inference/IndexFactor.h>
#include <gtsam/inference/SymbolicSequentialSolver.h> #include <gtsam/inference/SymbolicSequentialSolver.h>
using namespace std;
using namespace gtsam; using namespace gtsam;
typedef BayesTree<IndexConditional> SymbolicBayesTree; typedef BayesTree<IndexConditional> SymbolicBayesTree;

View File

@ -22,6 +22,7 @@
#include <gtsam/inference/VariableIndex.h> #include <gtsam/inference/VariableIndex.h>
#include <gtsam/inference/SymbolicFactorGraph.h> #include <gtsam/inference/SymbolicFactorGraph.h>
using namespace std;
using namespace gtsam; using namespace gtsam;
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -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 ; double gamma = s.vector().squaredNorm(), new_gamma = 0.0, alpha = 0.0, beta = 0.0 ;
const double threshold = const double threshold =
::max(parameters_.epsilon_abs(), std::max(parameters_.epsilon_abs(),
parameters_.epsilon() * parameters_.epsilon() * gamma); parameters_.epsilon() * parameters_.epsilon() * gamma);
const size_t iMaxIterations = parameters_.maxIterations(); const size_t iMaxIterations = parameters_.maxIterations();
const ConjugateGradientParameters::Verbosity verbosity = parameters_.cg_.verbosity(); const ConjugateGradientParameters::Verbosity verbosity = parameters_.cg_.verbosity();
if ( verbosity >= ConjugateGradientParameters::ERROR ) if ( verbosity >= ConjugateGradientParameters::ERROR )
cout << "[SimpleSPCGSolver] epsilon = " << parameters_.epsilon() std::cout << "[SimpleSPCGSolver] epsilon = " << parameters_.epsilon()
<< ", max = " << parameters_.maxIterations() << ", max = " << parameters_.maxIterations()
<< ", ||r0|| = " << std::sqrt(gamma) << ", ||r0|| = " << std::sqrt(gamma)
<< ", threshold = " << threshold << std::endl; << ", threshold = " << threshold << std::endl;
@ -122,14 +122,14 @@ VectorValues::shared_ptr SimpleSPCGSolver::optimize (const VectorValues &initial
gamma = new_gamma ; gamma = new_gamma ;
if ( verbosity >= ConjugateGradientParameters::ERROR) { 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 ; if ( gamma < threshold ) break ;
} // k } // k
if ( verbosity >= ConjugateGradientParameters::ERROR ) 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 */ /* transform y back to x */
return this->transform(*x); return this->transform(*x);

View File

@ -18,6 +18,8 @@
#include <cmath> #include <cmath>
#include <gtsam/nonlinear/DoglegOptimizerImpl.h> #include <gtsam/nonlinear/DoglegOptimizerImpl.h>
using namespace std;
namespace gtsam { namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues DoglegOptimizerImpl::ComputeDoglegPoint( VectorValues DoglegOptimizerImpl::ComputeDoglegPoint(

View File

@ -21,6 +21,8 @@
#include <gtsam/linear/GaussianMultifrontalSolver.h> #include <gtsam/linear/GaussianMultifrontalSolver.h>
#include <gtsam/nonlinear/Marginals.h> #include <gtsam/nonlinear/Marginals.h>
using namespace std;
namespace gtsam { namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -11,6 +11,8 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
using namespace std;
namespace gtsam { namespace gtsam {
/// Find the best total assignment - can be expensive /// Find the best total assignment - can be expensive

View File

@ -7,6 +7,8 @@
#include <gtsam_unstable/discrete/CSP.h> #include <gtsam_unstable/discrete/CSP.h>
#include <gtsam_unstable/discrete/Domain.h> #include <gtsam_unstable/discrete/Domain.h>
#include <boost/assign/std/map.hpp>
using boost::assign::insert;
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <iostream> #include <iostream>
#include <fstream> #include <fstream>

View File

@ -7,6 +7,8 @@
#include <gtsam_unstable/discrete/CSP.h> #include <gtsam_unstable/discrete/CSP.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <boost/assign/std/map.hpp>
using boost::assign::insert;
#include <iostream> #include <iostream>
#include <sstream> #include <sstream>
#include <stdarg.h> #include <stdarg.h>

View File

@ -7,6 +7,7 @@
#include <gtsam_unstable/dynamics/imuSystem.h> #include <gtsam_unstable/dynamics/imuSystem.h>
using namespace std;
using namespace gtsam; using namespace gtsam;
using namespace imu; using namespace imu;