From 4b8e65c1a40717f40f2fecb879fd92c6e402f0c3 Mon Sep 17 00:00:00 2001
From: Joan Sola <jsola@iri.upc.edu>
Date: Thu, 7 Apr 2016 23:29:04 +0200
Subject: [PATCH] Add namespace wolf surrounding classes in src/

---
 src/active_search.cpp                     |  4 ++
 src/active_search.h                       |  3 ++
 src/capture_base.cpp                      |  5 +++
 src/capture_base.h                        |  4 ++
 src/capture_fix.cpp                       |  3 ++
 src/capture_fix.h                         |  5 +++
 src/capture_gps.cpp                       |  3 ++
 src/capture_gps.h                         |  3 +-
 src/capture_gps_fix.cpp                   |  5 ++-
 src/capture_gps_fix.h                     |  4 ++
 src/capture_image.cpp                     |  3 ++
 src/capture_image.h                       |  4 ++
 src/capture_imu.cpp                       |  4 ++
 src/capture_imu.h                         |  4 ++
 src/capture_laser_2D.cpp                  |  3 ++
 src/capture_laser_2D.h                    |  4 ++
 src/capture_motion.cpp                    |  4 ++
 src/capture_motion.h                      |  6 +++
 src/capture_motion2.cpp                   |  3 ++
 src/capture_motion2.h                     |  3 ++
 src/capture_odom_2D.cpp                   |  2 +
 src/capture_odom_2D.h                     |  4 ++
 src/capture_odom_3D.cpp                   |  3 ++
 src/capture_odom_3D.h                     |  4 ++
 src/capture_void.cpp                      |  4 ++
 src/capture_void.h                        |  6 +++
 src/constraint_analytic.cpp               |  4 ++
 src/constraint_analytic.h                 |  4 ++
 src/constraint_base.cpp                   |  3 ++
 src/constraint_base.h                     |  3 ++
 src/constraint_container.h                |  5 +++
 src/constraint_corner_2D.h                |  4 ++
 src/constraint_fix.h                      |  5 +++
 src/constraint_gps_2D.h                   |  4 ++
 src/constraint_gps_pseudorange_2D.h       |  4 +-
 src/constraint_gps_pseudorange_3D.h       |  4 ++
 src/constraint_odom_2D.h                  |  5 +++
 src/constraint_odom_2D_analytic.h         |  5 +++
 src/constraint_relative_2D_analytic.h     |  4 ++
 src/constraint_sparse.h                   |  4 ++
 src/examples/test_wolf_tree.cpp           |  3 ++
 src/feature_base.cpp                      |  4 ++
 src/feature_base.h                        |  5 +++
 src/feature_corner_2D.cpp                 |  4 ++
 src/feature_corner_2D.h                   |  6 +++
 src/feature_fix.cpp                       |  5 +++
 src/feature_fix.h                         |  5 +++
 src/feature_gps_fix.cpp                   |  4 ++
 src/feature_gps_fix.h                     |  5 +++
 src/feature_gps_pseudorange.cpp           |  4 ++
 src/feature_gps_pseudorange.h             |  5 +++
 src/feature_odom_2D.cpp                   |  4 ++
 src/feature_odom_2D.h                     |  6 +++
 src/feature_point_image.cpp               |  5 +++
 src/feature_point_image.h                 |  6 +++
 src/frame_base.cpp                        |  4 ++
 src/frame_base.h                          |  4 ++
 src/hardware_base.cpp                     |  5 +++
 src/hardware_base.h                       |  4 ++
 src/landmark_base.cpp                     |  4 ++
 src/landmark_base.h                       |  3 ++
 src/landmark_container.cpp                |  4 ++
 src/landmark_container.h                  |  4 ++
 src/landmark_corner_2D.cpp                |  4 ++
 src/landmark_corner_2D.h                  |  5 +++
 src/local_parametrization_base.cpp        |  5 +++
 src/local_parametrization_base.h          |  6 +++
 src/local_parametrization_homogeneous.cpp |  4 ++
 src/local_parametrization_homogeneous.h   |  5 +++
 src/local_parametrization_quaternion.cpp  |  4 ++
 src/local_parametrization_quaternion.h    |  6 +++
 src/map_base.cpp                          |  5 +++
 src/map_base.h                            |  4 ++
 src/node_base.cpp                         |  3 ++
 src/node_base.h                           |  5 +++
 src/node_constrained.h                    |  5 +++
 src/node_linked.h                         |  5 ++-
 src/node_terminus.h                       |  4 ++
 src/processor_ORB.cpp                     |  4 ++
 src/processor_ORB.h                       |  4 ++
 src/processor_base.cpp                    |  5 +++
 src/processor_base.h                      |  5 +++
 src/processor_brisk.cpp                   |  4 ++
 src/processor_brisk.h                     |  5 +++
 src/processor_gps.cpp                     |  4 ++
 src/processor_gps.h                       |  5 +++
 src/processor_laser_2D.cpp                |  3 ++
 src/processor_laser_2D.h                  |  4 ++
 src/processor_motion.cpp                  |  7 +++-
 src/processor_motion.h                    |  4 ++
 src/processor_odom_3D.h                   |  5 +++
 src/processor_preintegrated_imu.cpp       |  3 ++
 src/processor_preintegrated_imu.h         |  4 ++
 src/processor_tracker.cpp                 |  4 +-
 src/processor_tracker.h                   |  4 ++
 src/processor_tracker_feature.cpp         |  4 ++
 src/processor_tracker_feature.h           |  4 ++
 src/processor_tracker_laser.cpp           |  3 ++
 src/processor_tracker_laser.h             |  6 +++
 src/sensor_base.cpp                       |  5 +++
 src/sensor_base.h                         |  4 ++
 src/sensor_camera.cpp                     |  5 +++
 src/sensor_camera.h                       |  5 +++
 src/sensor_gps.cpp                        |  3 ++
 src/sensor_gps.h                          |  5 +++
 src/sensor_gps_fix.cpp                    |  5 +++
 src/sensor_gps_fix.h                      |  6 +++
 src/sensor_imu.cpp                        |  3 ++
 src/sensor_imu.h                          |  5 +++
 src/sensor_laser_2D.cpp                   |  4 ++
 src/sensor_laser_2D.h                     |  7 ++++
 src/sensor_odom_2D.cpp                    |  4 ++
 src/sensor_odom_2D.h                      |  5 +++
 src/state_block.cpp                       |  4 ++
 src/state_block.h                         |  5 +++
 src/state_homogeneous_3d.cpp              |  3 ++
 src/state_homogeneous_3d.h                |  4 ++
 src/state_quaternion.cpp                  |  3 ++
 src/state_quaternion.h                    |  4 ++
 src/tf.h                                  |  4 ++
 src/time_stamp.cpp                        |  3 ++
 src/time_stamp.h                          |  4 ++
 src/trajectory_base.cpp                   |  3 ++
 src/trajectory_base.h                     |  6 +++
 src/wolf.h                                | 50 +++++++++++++----------
 src/wolf_manager.cpp                      |  4 ++
 src/wolf_manager.h                        |  5 +++
 src/wolf_problem.cpp                      |  4 ++
 src/wolf_problem.h                        |  6 +++
 129 files changed, 573 insertions(+), 27 deletions(-)

diff --git a/src/active_search.cpp b/src/active_search.cpp
index d402986dc..7f0533483 100644
--- a/src/active_search.cpp
+++ b/src/active_search.cpp
@@ -6,6 +6,8 @@
 
 #include "active_search.h"
 
+namespace wolf{
+
 // CLASS ActiveSearchGrid
 ActiveSearchGrid::ActiveSearchGrid(const int & _img_size_h, const int & _img_size_v, const int & _n_cells_h,
                                    const int & _n_cells_v, const int & _margin, const int & _separation) :
@@ -139,3 +141,5 @@ void ActiveSearchGrid::blockCell(const cv::Rect & _roi)
         }
 #endif
 */
+
+}
diff --git a/src/active_search.h b/src/active_search.h
index 818cd3ac3..8097f4a8f 100644
--- a/src/active_search.h
+++ b/src/active_search.h
@@ -19,6 +19,7 @@
 //OpenCV includes
 #include <opencv2/core/core.hpp>
 
+namespace wolf{
 
 /**
          * Active search tesselation grid.
@@ -252,4 +253,6 @@ inline Eigen::Vector2i ActiveSearchGrid::cellCenter(const Eigen::Vector2i& _cell
 //		};
 //#endif
 
+}
+
 #endif /* ACTIVESEARCH_HPP_ */
diff --git a/src/capture_base.cpp b/src/capture_base.cpp
index ff9902acf..abab1aec6 100644
--- a/src/capture_base.cpp
+++ b/src/capture_base.cpp
@@ -3,6 +3,9 @@
 #include "sensor_base.h"
 #include "feature_base.h"
 
+namespace wolf{
+
+
 CaptureBase::CaptureBase(const TimeStamp& _ts, SensorBase* _sensor_ptr) :
         NodeLinked(MID, "CAPTURE"),
         time_stamp_(_ts),
@@ -49,3 +52,5 @@ StateBlock* CaptureBase::getSensorOPtr() const {
 		return getSensorPtr()->getOPtr();
 }
 
+}
+
diff --git a/src/capture_base.h b/src/capture_base.h
index 2fadede15..2c08af62a 100644
--- a/src/capture_base.h
+++ b/src/capture_base.h
@@ -14,6 +14,8 @@ class SensorBase;
 //std includes
 //
 
+namespace wolf{
+
 
 //class CaptureBase
 class CaptureBase : public NodeLinked<FrameBase, FeatureBase>
@@ -119,4 +121,6 @@ inline void CaptureBase::setTimeStampToNow()
     time_stamp_.setToNow();
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/capture_fix.cpp b/src/capture_fix.cpp
index ce0e9f73c..fb899a701 100644
--- a/src/capture_fix.cpp
+++ b/src/capture_fix.cpp
@@ -1,5 +1,6 @@
 #include "capture_fix.h"
 
+namespace wolf{
 
 CaptureFix::CaptureFix(const TimeStamp& _ts, SensorBase* _sensor_ptr, const Eigen::VectorXs& _data, const Eigen::MatrixXs& _data_covariance) :
 	CaptureBase(_ts, _sensor_ptr),
@@ -29,3 +30,5 @@ Eigen::VectorXs CaptureFix::computeFramePose(const TimeStamp& _now) const
 {
 	return data_;
 }
+
+} // namespace wolf
diff --git a/src/capture_fix.h b/src/capture_fix.h
index 183d48062..781a35c56 100644
--- a/src/capture_fix.h
+++ b/src/capture_fix.h
@@ -9,6 +9,9 @@
 //std includes
 //
 
+namespace wolf {
+
+
 //class CaptureFix
 class CaptureFix : public CaptureBase
 {
@@ -31,4 +34,6 @@ class CaptureFix : public CaptureBase
 
         virtual Eigen::VectorXs computeFramePose(const TimeStamp& _now) const;
 };
+
+} //namespace wolf
 #endif
diff --git a/src/capture_gps.cpp b/src/capture_gps.cpp
index 98e6c4282..02bd54adf 100644
--- a/src/capture_gps.cpp
+++ b/src/capture_gps.cpp
@@ -1,5 +1,6 @@
 #include "capture_gps.h"
 
+namespace wolf {
 
 CaptureGPS::CaptureGPS(const TimeStamp &_ts, SensorBase *_sensor_ptr, rawgpsutils::SatellitesObs &_obs) :
         CaptureBase(_ts, _sensor_ptr),
@@ -29,3 +30,5 @@ Eigen::VectorXs CaptureGPS::computeFramePose(const TimeStamp &_now) const
 {
     return Eigen::Vector3s(0, 0, 0);
 }
+
+} //namespace wolf
diff --git a/src/capture_gps.h b/src/capture_gps.h
index 89456972e..5904e3706 100644
--- a/src/capture_gps.h
+++ b/src/capture_gps.h
@@ -6,6 +6,7 @@
 #include "raw_gps_utils/satellites_obs.h"
 #include "capture_base.h"
 
+namespace wolf {
 
 class CaptureGPS : public CaptureBase
 {
@@ -33,6 +34,6 @@ public:
 
 };
 
-
+} // namespace wolf
 
 #endif //CAPTURE_GPS_H_
diff --git a/src/capture_gps_fix.cpp b/src/capture_gps_fix.cpp
index 71ec8da80..1e27c5c9b 100644
--- a/src/capture_gps_fix.cpp
+++ b/src/capture_gps_fix.cpp
@@ -1,5 +1,8 @@
 #include "capture_gps_fix.h"
 
+
+namespace wolf {
+
 CaptureGPSFix::CaptureGPSFix(const TimeStamp& _ts, SensorBase* _sensor_ptr, const Eigen::VectorXs& _data) :
 	CaptureBase(_ts, _sensor_ptr),
 	data_(_data)
@@ -44,4 +47,4 @@ Eigen::VectorXs CaptureGPSFix::computeFramePose(const TimeStamp& _now) const
 //}
 
 
-
+} //namespace wolf
diff --git a/src/capture_gps_fix.h b/src/capture_gps_fix.h
index 343cbbaee..c57d9b9f6 100644
--- a/src/capture_gps_fix.h
+++ b/src/capture_gps_fix.h
@@ -8,6 +8,8 @@
 //std includes
 //
 
+namespace wolf {
+
 //class CaptureGPSFix
 class CaptureGPSFix : public CaptureBase
 {
@@ -33,4 +35,6 @@ class CaptureGPSFix : public CaptureBase
 
         //virtual void printSelf(unsigned int _ntabs = 0, std::ostream & _ost = std::cout) const;
 };
+
+} //namespace wolf
 #endif
diff --git a/src/capture_image.cpp b/src/capture_image.cpp
index f3b9fc89b..c77173896 100644
--- a/src/capture_image.cpp
+++ b/src/capture_image.cpp
@@ -1,6 +1,8 @@
 #include "capture_image.h"
 #include <opencv2/core/core.hpp>
 
+namespace wolf {
+
 CaptureImage::CaptureImage(const TimeStamp& _ts, SensorCamera* _camera_ptr, cv::Mat _data_cv, int _img_width, int _img_height) :
     CaptureBase(_ts, _camera_ptr), image_(_data_cv)
 {
@@ -45,3 +47,4 @@ Eigen::VectorXs CaptureImage::computeFramePose(const TimeStamp& _now) const
     return Eigen::VectorXs::Zero(7);
 }
 
+} // namespace wolf
diff --git a/src/capture_image.h b/src/capture_image.h
index 6b9f2480e..57afb0ad6 100644
--- a/src/capture_image.h
+++ b/src/capture_image.h
@@ -12,6 +12,8 @@
 //std includes
 //
 
+namespace wolf {
+
 //class CaptureImage
 class CaptureImage : public CaptureBase
 {
@@ -53,4 +55,6 @@ class CaptureImage : public CaptureBase
 
 };
 
+} // namespace wolf
+
 #endif // CAPTURE_IMAGE_H
diff --git a/src/capture_imu.cpp b/src/capture_imu.cpp
index d617feddc..66cfc4d50 100644
--- a/src/capture_imu.cpp
+++ b/src/capture_imu.cpp
@@ -1,5 +1,7 @@
 #include "capture_imu.h"
 
+namespace wolf {
+
 
 CaptureIMU::CaptureIMU(const TimeStamp& _init_ts, const TimeStamp& _final_ts, SensorBase* _sensor_ptr,
                              const Eigen::Vector6s& _data) :
@@ -46,3 +48,5 @@ CaptureIMU* CaptureIMU::interpolateCapture(const TimeStamp& _ts)
 
 }
 
+} //namespace wolf
+
diff --git a/src/capture_imu.h b/src/capture_imu.h
index 0dbc85db8..1e35f2ed7 100644
--- a/src/capture_imu.h
+++ b/src/capture_imu.h
@@ -6,6 +6,8 @@
 #include "feature_base.h" //must be replaced by feature_imu if needed
 #include "sensor_base.h" //must be replaced by sensor_imu
 
+namespace wolf {
+
 class CaptureIMU : public CaptureMotion
 {
     public:
@@ -32,4 +34,6 @@ class CaptureIMU : public CaptureMotion
         virtual CaptureIMU* interpolateCapture(const TimeStamp& _ts);
 };
 
+} // namespace wolf
+
 #endif // CAPTURE_IMU_H
diff --git a/src/capture_laser_2D.cpp b/src/capture_laser_2D.cpp
index a84cd73e2..f9b3f4b6b 100644
--- a/src/capture_laser_2D.cpp
+++ b/src/capture_laser_2D.cpp
@@ -1,5 +1,7 @@
 #include "capture_laser_2D.h"
 
+namespace wolf {
+
 // unsigned int CaptureLaser2D::segment_window_size = 8;//window size to extract segments
 // double CaptureLaser2D::theta_min = 0.4; //minimum theta between consecutive segments to detect corner. PI/8=0.39
 // double CaptureLaser2D::theta_max_parallel = 0.1; //maximum theta between consecutive segments to fuse them in a single line.
@@ -42,3 +44,4 @@ Eigen::VectorXs CaptureLaser2D::computeFramePose(const TimeStamp& _now) const
     return Eigen::Vector3s(1, 2, 3);
 }
 
+} // namespace wolf
diff --git a/src/capture_laser_2D.h b/src/capture_laser_2D.h
index 7d3c09eee..dc4f3a763 100644
--- a/src/capture_laser_2D.h
+++ b/src/capture_laser_2D.h
@@ -7,6 +7,8 @@
 //wolf includes
 #include "capture_base.h"
 
+namespace wolf {
+
 class CaptureLaser2D : public CaptureBase
 {
     public:
@@ -52,4 +54,6 @@ inline const std::vector<float>& CaptureLaser2D::getRanges() const
     return ranges_;
 }
 
+} // namespace wolf
+
 #endif /* CAPTURE_LASER_2D_H_ */
diff --git a/src/capture_motion.cpp b/src/capture_motion.cpp
index 73b3a26f4..f41f7b677 100644
--- a/src/capture_motion.cpp
+++ b/src/capture_motion.cpp
@@ -1,5 +1,7 @@
 #include "capture_motion.h"
 
+namespace wolf {
+
 CaptureMotion::CaptureMotion(const TimeStamp& _init_ts, const TimeStamp& _final_ts, SensorBase* _sensor_ptr, const Eigen::VectorXs& _data) :
 	CaptureBase(_init_ts, _sensor_ptr),
 	data_(_data),
@@ -40,3 +42,5 @@ void CaptureMotion::setFinalTimeStamp(const TimeStamp & _ts)
 {
     final_time_stamp_ = _ts;
 }
+
+} // namespace wolf
diff --git a/src/capture_motion.h b/src/capture_motion.h
index 1bd03ca83..a13b96961 100644
--- a/src/capture_motion.h
+++ b/src/capture_motion.h
@@ -9,6 +9,9 @@
 //std includes
 //
 
+
+namespace wolf {
+
 //class CaptureBase
 class CaptureMotion : public CaptureBase
 {
@@ -59,4 +62,7 @@ class CaptureMotion : public CaptureBase
         virtual Eigen::VectorXs computeFramePose(const TimeStamp& _now) const = 0;
 
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/capture_motion2.cpp b/src/capture_motion2.cpp
index af4955311..8f9e92ca3 100644
--- a/src/capture_motion2.cpp
+++ b/src/capture_motion2.cpp
@@ -20,3 +20,6 @@
 // ATENTION: This cpp file should remain empty to allow this class to be fully inlined.
 // ATENTION
 // ATENTION
+namespace wolf {
+
+}
diff --git a/src/capture_motion2.h b/src/capture_motion2.h
index 23104c6b2..4d0dd964e 100644
--- a/src/capture_motion2.h
+++ b/src/capture_motion2.h
@@ -16,6 +16,8 @@
 #include <algorithm>
 #include <iterator>
 
+namespace wolf {
+
 /** \brief Base class for motion Captures.
  * \param MotionDeltaType The type of the motion delta and the motion integrated delta. It can be an Eigen::VectorXs (default) or any other construction, most likely a struct.
  *        Generalized Delta types allow for optimized algorithms.
@@ -161,5 +163,6 @@ class CaptureMotion2 : public CaptureBase
         MotionBuffer buffer_; ///< Buffer of motions between this Capture and the next one.
 };
 
+} // namespace wolf
 
 #endif /* SRC_CAPTURE_MOTION2_H_ */
diff --git a/src/capture_odom_2D.cpp b/src/capture_odom_2D.cpp
index 99b46d6bb..fc86a3264 100644
--- a/src/capture_odom_2D.cpp
+++ b/src/capture_odom_2D.cpp
@@ -1,5 +1,6 @@
 #include "capture_odom_2D.h"
 
+namespace wolf {
 
 CaptureOdom2D::CaptureOdom2D(const TimeStamp& _init_ts, const TimeStamp& _final_ts, SensorBase* _sensor_ptr,
                              const Eigen::Vector3s& _data) :
@@ -110,3 +111,4 @@ CaptureOdom2D* CaptureOdom2D::interpolateCapture(const TimeStamp& _ts)
     return second_odom_ptr;
 }
 
+} // namespace wolf
diff --git a/src/capture_odom_2D.h b/src/capture_odom_2D.h
index e45bdcdaa..f7dc04244 100644
--- a/src/capture_odom_2D.h
+++ b/src/capture_odom_2D.h
@@ -10,6 +10,8 @@
 //std includes
 //
 
+namespace wolf {
+
 class CaptureOdom2D : public CaptureMotion
 {
 
@@ -37,4 +39,6 @@ class CaptureOdom2D : public CaptureMotion
       virtual CaptureOdom2D* interpolateCapture(const TimeStamp& _ts);
 
 };
+
+} // namespace wolf
 #endif
diff --git a/src/capture_odom_3D.cpp b/src/capture_odom_3D.cpp
index 7dd1c39bc..56b4f5ad3 100644
--- a/src/capture_odom_3D.cpp
+++ b/src/capture_odom_3D.cpp
@@ -20,3 +20,6 @@
 // ATENTION: This cpp file should remain empty to allow this class to be fully inlined.
 // ATENTION
 // ATENTION
+namespace wolf {
+
+}
diff --git a/src/capture_odom_3D.h b/src/capture_odom_3D.h
index 548eae06b..96acc4303 100644
--- a/src/capture_odom_3D.h
+++ b/src/capture_odom_3D.h
@@ -12,6 +12,8 @@
 
 #include "processor_odom_3D.h"
 
+namespace wolf {
+
 // Declare the class
 class CaptureOdom3D : public CaptureMotion2<Odom3dDelta>
 {
@@ -32,4 +34,6 @@ inline CaptureOdom3D::CaptureOdom3D(const TimeStamp& _ts, SensorBase* _sensor_pt
     //
 }
 
+} // namespace wolf
+
 #endif /* CAPTURE_ODOM_3D_H_ */
diff --git a/src/capture_void.cpp b/src/capture_void.cpp
index 06966eed5..6f2d9724a 100644
--- a/src/capture_void.cpp
+++ b/src/capture_void.cpp
@@ -1,5 +1,7 @@
 #include "capture_void.h"
 
+namespace wolf {
+
 CaptureVoid::CaptureVoid(const TimeStamp& _ts, SensorBase* _sensor_ptr) :
     CaptureBase(_ts, _sensor_ptr)
 {
@@ -15,3 +17,5 @@ Eigen::VectorXs CaptureVoid::computeFramePose(const TimeStamp& _now) const
 {
     return Eigen::VectorXs::Zero(3);
 }
+
+} // namespace wolf
diff --git a/src/capture_void.h b/src/capture_void.h
index 03cf49d94..8bf009ef5 100644
--- a/src/capture_void.h
+++ b/src/capture_void.h
@@ -4,6 +4,9 @@
 //Wolf includes
 #include "capture_base.h"
 
+
+namespace wolf {
+
 //class CaptureVoid
 class CaptureVoid : public CaptureBase
 {
@@ -19,4 +22,7 @@ class CaptureVoid : public CaptureBase
 
         virtual Eigen::VectorXs computeFramePose(const TimeStamp& _now) const;
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_analytic.cpp b/src/constraint_analytic.cpp
index e8d17de4f..148ac34d7 100644
--- a/src/constraint_analytic.cpp
+++ b/src/constraint_analytic.cpp
@@ -1,6 +1,8 @@
 #include "constraint_analytic.h"
 #include "state_block.h"
 
+namespace wolf {
+
 ConstraintAnalytic::ConstraintAnalytic(FeatureBase* _ftr_ptr, ConstraintType _tp, ConstraintStatus _status,
                                        StateBlock* _state0Ptr, StateBlock* _state1Ptr, StateBlock* _state2Ptr, StateBlock* _state3Ptr, StateBlock* _state4Ptr,
                                        StateBlock* _state5Ptr, StateBlock* _state6Ptr, StateBlock* _state7Ptr, StateBlock* _state8Ptr, StateBlock* _state9Ptr ) :
@@ -174,3 +176,5 @@ void ConstraintAnalytic::resizeVectors()
         }
     }
 }
+
+} // namespace wolf
diff --git a/src/constraint_analytic.h b/src/constraint_analytic.h
index 2b6e36938..1620d6e66 100644
--- a/src/constraint_analytic.h
+++ b/src/constraint_analytic.h
@@ -6,6 +6,8 @@
 #include "wolf.h"
 #include "constraint_base.h"
 
+namespace wolf {
+
 class ConstraintAnalytic: public ConstraintBase
 {
     protected:
@@ -157,4 +159,6 @@ class ConstraintAnalytic: public ConstraintBase
         void resizeVectors();
 };
 
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_base.cpp b/src/constraint_base.cpp
index e97c622a7..4bea33f18 100644
--- a/src/constraint_base.cpp
+++ b/src/constraint_base.cpp
@@ -3,6 +3,7 @@
 #include "node_terminus.h"
 #include "landmark_base.h"
 
+namespace wolf {
 
 ConstraintBase::ConstraintBase(ConstraintType _tp, ConstraintStatus _status) :
     NodeLinked(BOTTOM, "CONSTRAINT"),
@@ -113,3 +114,5 @@ void ConstraintBase::setStatus(ConstraintStatus _status)
     }
     status_ = _status;
 }
+
+} // namespace wolf
diff --git a/src/constraint_base.h b/src/constraint_base.h
index 3577c1b36..a307b08fb 100644
--- a/src/constraint_base.h
+++ b/src/constraint_base.h
@@ -12,6 +12,8 @@ class NodeTerminus;
 //std includes
 //
 
+namespace wolf {
+
 //TODO: add a member to indicate how jacobian is computed, called "jacobian_method_"
 //class ConstraintBase
 class ConstraintBase : public NodeLinked<FeatureBase, NodeTerminus>
@@ -150,4 +152,5 @@ inline LandmarkBase* ConstraintBase::getLandmarkOtherPtr()
     return landmark_ptr_;
 }
 
+} // namespace wolf
 #endif
diff --git a/src/constraint_container.h b/src/constraint_container.h
index 5552e7ff4..c92162372 100644
--- a/src/constraint_container.h
+++ b/src/constraint_container.h
@@ -6,6 +6,8 @@
 #include "constraint_sparse.h"
 #include "landmark_container.h"
 
+namespace wolf {
+
 class ConstraintContainer: public ConstraintSparse<3,2,1,2,1>
 {
 	protected:
@@ -133,4 +135,7 @@ class ConstraintContainer: public ConstraintSparse<3,2,1,2,1>
             return JAC_AUTO;
         }
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_corner_2D.h b/src/constraint_corner_2D.h
index 7ca92c3e6..e73d6dab2 100644
--- a/src/constraint_corner_2D.h
+++ b/src/constraint_corner_2D.h
@@ -6,6 +6,8 @@
 #include "constraint_sparse.h"
 #include "landmark_corner_2D.h"
 
+namespace wolf {
+
 class ConstraintCorner2D: public ConstraintSparse<3,2,1,2,1>
 {
 	public:
@@ -117,4 +119,6 @@ inline bool ConstraintCorner2D::operator ()(const T* const _robotP, const T* con
     return true;
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_fix.h b/src/constraint_fix.h
index 6f7627d95..0e67338df 100644
--- a/src/constraint_fix.h
+++ b/src/constraint_fix.h
@@ -6,6 +6,9 @@
 #include "wolf.h"
 #include "constraint_sparse.h"
 
+
+namespace wolf {
+
 class ConstraintFix: public ConstraintSparse<3,2,1>
 {
     public:
@@ -65,4 +68,6 @@ inline bool ConstraintFix::operator ()(const T* const _p, const T* const _o, T*
     return true;
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_gps_2D.h b/src/constraint_gps_2D.h
index 0e7bec61f..0f3610817 100644
--- a/src/constraint_gps_2D.h
+++ b/src/constraint_gps_2D.h
@@ -6,6 +6,8 @@
 #include "wolf.h"
 #include "constraint_sparse.h"
 
+namespace wolf {
+
 class ConstraintGPS2D : public ConstraintSparse<2, 2>
 {
     public:
@@ -49,4 +51,6 @@ inline bool ConstraintGPS2D::operator ()(const T* const _x, T* _residuals) const
     return true;
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_gps_pseudorange_2D.h b/src/constraint_gps_pseudorange_2D.h
index 9b4623208..4c28b6e99 100644
--- a/src/constraint_gps_pseudorange_2D.h
+++ b/src/constraint_gps_pseudorange_2D.h
@@ -12,6 +12,8 @@
 #include <string>
 #include <sstream>
 
+namespace wolf {
+
 /*
  * NB:
  * FROM THIS CLASS AND ALL THE CLASS INCLUDED, THE LIBRARY RAW_GPS_UTILS
@@ -247,6 +249,6 @@ inline bool ConstraintGPSPseudorange2D::operator ()(const T* const _vehicle_p, c
     return true;
 }
 
-
+} // namespace wolf
 
 #endif //CONSTRAINT_GPS_PSEUDORANGE_2D_H_
diff --git a/src/constraint_gps_pseudorange_3D.h b/src/constraint_gps_pseudorange_3D.h
index c8723bdc2..5e7b22ad8 100644
--- a/src/constraint_gps_pseudorange_3D.h
+++ b/src/constraint_gps_pseudorange_3D.h
@@ -8,6 +8,8 @@
 #include "feature_gps_pseudorange.h"
 #include "constraint_sparse.h"
 
+namespace wolf {
+
 /*
  * NB:
  * FROM THIS CLASS AND ALL THE CLASS INCLUDED, THE LIBRARY RAW_GPS_UTILS
@@ -143,4 +145,6 @@ inline bool ConstraintGPSPseudorange3D::operator ()(const T* const _vehicle_p, c
     return true;
 }
 
+} // namespace wolf
+
 #endif //CONSTRAINT_GPS_PSEUDORANGE_3D_H_
diff --git a/src/constraint_odom_2D.h b/src/constraint_odom_2D.h
index 953f25cce..f04a0f60c 100644
--- a/src/constraint_odom_2D.h
+++ b/src/constraint_odom_2D.h
@@ -5,6 +5,8 @@
 #include "wolf.h"
 #include "constraint_sparse.h"
 
+namespace wolf {
+
 class ConstraintOdom2D : public ConstraintSparse<3, 2, 1, 2, 1>
 {
     public:
@@ -90,4 +92,7 @@ inline bool ConstraintOdom2D::operator ()(const T* const _p1, const T* const _o1
     return true;
 }
 
+
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_odom_2D_analytic.h b/src/constraint_odom_2D_analytic.h
index 1b70a1e00..b45ee9c82 100644
--- a/src/constraint_odom_2D_analytic.h
+++ b/src/constraint_odom_2D_analytic.h
@@ -5,6 +5,8 @@
 #include "wolf.h"
 #include "constraint_relative_2D_analytic.h"
 
+namespace wolf {
+
 class ConstraintOdom2DAnalytic : public ConstraintRelative2DAnalytic
 {
     public:
@@ -101,4 +103,7 @@ class ConstraintOdom2DAnalytic : public ConstraintRelative2DAnalytic
 //            return AUTO;
 //        }
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_relative_2D_analytic.h b/src/constraint_relative_2D_analytic.h
index 8a9a4a3df..1f51f61a2 100644
--- a/src/constraint_relative_2D_analytic.h
+++ b/src/constraint_relative_2D_analytic.h
@@ -6,6 +6,8 @@
 #include "constraint_analytic.h"
 #include "landmark_base.h"
 
+namespace wolf {
+
 class ConstraintRelative2DAnalytic : public ConstraintAnalytic
 {
     public:
@@ -162,4 +164,6 @@ inline void ConstraintRelative2DAnalytic::evaluatePureJacobians(std::vector<Eige
     jacobians[3] << 0, 0, 1;
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/constraint_sparse.h b/src/constraint_sparse.h
index 5a03a341c..497927ff2 100644
--- a/src/constraint_sparse.h
+++ b/src/constraint_sparse.h
@@ -7,6 +7,8 @@
 #include "constraint_base.h"
 #include "state_block.h"
 
+namespace wolf {
+
 //TODO: change class name (and file name!->includes) to ConstraintNumericalAutoDiff 
 //template class ConstraintSparse
 template <const unsigned int MEASUREMENT_SIZE,
@@ -533,4 +535,6 @@ void ConstraintSparse<MEASUREMENT_SIZE,
     }
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/examples/test_wolf_tree.cpp b/src/examples/test_wolf_tree.cpp
index 17bf56dba..9e273a399 100644
--- a/src/examples/test_wolf_tree.cpp
+++ b/src/examples/test_wolf_tree.cpp
@@ -10,6 +10,7 @@
 //Wolf includes
 #include "wolf_manager.h"
 
+namespace wolf {
 
 int main(int argc, char** argv) 
 {
@@ -55,3 +56,5 @@ int main(int argc, char** argv)
     //exit
     return 0;
 }
+
+} // namespace wolf
diff --git a/src/feature_base.cpp b/src/feature_base.cpp
index 9958de514..12bc69abc 100644
--- a/src/feature_base.cpp
+++ b/src/feature_base.cpp
@@ -2,6 +2,8 @@
 #include "constraint_base.h"
 #include "capture_base.h"
 
+namespace wolf {
+
 FeatureBase::FeatureBase(FeatureType _tp, unsigned int _dim_measurement) :
     NodeConstrained(MID, "FEATURE"),
     type_(_tp),
@@ -66,3 +68,5 @@ void FeatureBase::setMeasurementCovariance(const Eigen::MatrixXs & _meas_cov)
     measurement_sqrt_information_ = measurement_sqrt_covariance.inverse(); // retrieve factor U  in the decomposition
 }
 
+
+} // namespace wolf
diff --git a/src/feature_base.h b/src/feature_base.h
index 54ee2292e..7715661cf 100644
--- a/src/feature_base.h
+++ b/src/feature_base.h
@@ -12,6 +12,9 @@ class ConstraintBase;
 
 //std includes
 
+
+namespace wolf {
+
 //class FeatureBase
 class FeatureBase : public NodeConstrained<CaptureBase,ConstraintBase>
 {
@@ -111,4 +114,6 @@ inline void FeatureBase::setMeasurement(const Eigen::VectorXs& _meas)
     measurement_ = _meas;
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/feature_corner_2D.cpp b/src/feature_corner_2D.cpp
index 969dfe37c..ce4a025e1 100644
--- a/src/feature_corner_2D.cpp
+++ b/src/feature_corner_2D.cpp
@@ -1,6 +1,8 @@
 
 #include "feature_corner_2D.h"
 
+namespace wolf {
+
 FeatureCorner2D::FeatureCorner2D(const Eigen::Vector4s & _measurement, const Eigen::Matrix4s & _meas_covariance) :
     FeatureBase(FEAT_CORNER, _measurement, _meas_covariance)
 {
@@ -16,3 +18,5 @@ WolfScalar FeatureCorner2D::getAperture() const
 {
     return measurement_(3);
 }
+
+} // namespace wolf
diff --git a/src/feature_corner_2D.h b/src/feature_corner_2D.h
index 505467291..cab19ab23 100644
--- a/src/feature_corner_2D.h
+++ b/src/feature_corner_2D.h
@@ -7,6 +7,9 @@
 //std includes
 //
 
+
+namespace wolf {
+
 //class FeatureCorner2D
 class FeatureCorner2D : public FeatureBase
 {
@@ -32,4 +35,7 @@ class FeatureCorner2D : public FeatureBase
         WolfScalar getAperture() const; 
         
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/feature_fix.cpp b/src/feature_fix.cpp
index 08f2a65e3..578b9bb3b 100644
--- a/src/feature_fix.cpp
+++ b/src/feature_fix.cpp
@@ -1,5 +1,8 @@
 #include "feature_fix.h"
 
+
+namespace wolf {
+
 FeatureFix::FeatureFix(const Eigen::VectorXs& _measurement, const Eigen::MatrixXs& _meas_covariance) :
     FeatureBase(FEAT_FIX, _measurement, _meas_covariance)
 {
@@ -10,3 +13,5 @@ FeatureFix::~FeatureFix()
 {
     //
 }
+
+} // namespace wolf
diff --git a/src/feature_fix.h b/src/feature_fix.h
index ecee0b2fd..c2c4c2d39 100644
--- a/src/feature_fix.h
+++ b/src/feature_fix.h
@@ -8,6 +8,8 @@
 //std includes
 //
 
+namespace wolf {
+
 //class FeatureFix
 class FeatureFix : public FeatureBase
 {
@@ -28,4 +30,7 @@ class FeatureFix : public FeatureBase
          **/
         virtual ~FeatureFix();
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/feature_gps_fix.cpp b/src/feature_gps_fix.cpp
index ada0134d6..8b696e06e 100644
--- a/src/feature_gps_fix.cpp
+++ b/src/feature_gps_fix.cpp
@@ -1,5 +1,7 @@
 #include "feature_gps_fix.h"
 
+namespace wolf {
+
 FeatureGPSFix::FeatureGPSFix(unsigned int _dim_measurement) :
     FeatureBase(FEAT_GPS_FIX, _dim_measurement)
 {
@@ -16,3 +18,5 @@ FeatureGPSFix::~FeatureGPSFix()
 {
     //
 }
+
+} // namespace wolf
diff --git a/src/feature_gps_fix.h b/src/feature_gps_fix.h
index 3a66d154a..1569776f6 100644
--- a/src/feature_gps_fix.h
+++ b/src/feature_gps_fix.h
@@ -7,6 +7,8 @@
 
 //std includes
 
+namespace wolf {
+
 //class FeatureGPSFix
 class FeatureGPSFix : public FeatureBase
 {
@@ -33,4 +35,7 @@ class FeatureGPSFix : public FeatureBase
          **/
         virtual ~FeatureGPSFix();
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/feature_gps_pseudorange.cpp b/src/feature_gps_pseudorange.cpp
index 32640e196..096038437 100644
--- a/src/feature_gps_pseudorange.cpp
+++ b/src/feature_gps_pseudorange.cpp
@@ -1,5 +1,7 @@
 #include "feature_gps_pseudorange.h"
 
+namespace wolf {
+
 FeatureGPSPseudorange::FeatureGPSPseudorange(Eigen::Vector3s &_sat_position, WolfScalar _pseudorange, WolfScalar _covariance) :
         FeatureBase(FEAT_GPS_PR, Eigen::VectorXs::Constant(1,_pseudorange), Eigen::MatrixXs::Identity(1,1)*_covariance),
         sat_position_(_sat_position),
@@ -26,3 +28,5 @@ const Eigen::Vector3s &FeatureGPSPseudorange::getSatPosition() const
 {
     return sat_position_;
 }
+
+} // namespace wolf
diff --git a/src/feature_gps_pseudorange.h b/src/feature_gps_pseudorange.h
index dae86d010..922ad001d 100644
--- a/src/feature_gps_pseudorange.h
+++ b/src/feature_gps_pseudorange.h
@@ -8,6 +8,10 @@
 //std includes
 #include <iomanip>
 
+
+namespace wolf {
+
+
 // TODO manage covariance
 
 class FeatureGPSPseudorange : public FeatureBase
@@ -32,5 +36,6 @@ public:
 
 };
 
+} // namespace wolf
 
 #endif //FEATURE_GPS_PSEUDORANGE_H_
diff --git a/src/feature_odom_2D.cpp b/src/feature_odom_2D.cpp
index 5d1939b0c..80a434d97 100644
--- a/src/feature_odom_2D.cpp
+++ b/src/feature_odom_2D.cpp
@@ -1,5 +1,7 @@
 #include "feature_odom_2D.h"
 
+namespace wolf {
+
 FeatureOdom2D::FeatureOdom2D(unsigned int _dim_measurement) :
     FeatureBase(FEAT_ODOM_2D, _dim_measurement)
 {
@@ -21,3 +23,5 @@ void FeatureOdom2D::findConstraints()
 {
 
 }
+
+} // namespace wolf
diff --git a/src/feature_odom_2D.h b/src/feature_odom_2D.h
index fd489cfed..1b7f74d6c 100644
--- a/src/feature_odom_2D.h
+++ b/src/feature_odom_2D.h
@@ -8,6 +8,9 @@
 
 //std includes
 
+
+namespace wolf {
+
 //class FeatureOdom2D
 class FeatureOdom2D : public FeatureBase
 {
@@ -43,4 +46,7 @@ class FeatureOdom2D : public FeatureBase
         virtual void findConstraints();
         
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/feature_point_image.cpp b/src/feature_point_image.cpp
index c4661e111..551e5acce 100644
--- a/src/feature_point_image.cpp
+++ b/src/feature_point_image.cpp
@@ -7,6 +7,9 @@
  *
  **/
 
+
+namespace wolf {
+
 FeaturePointImage::FeaturePointImage(const Eigen::Vector2s & _measurement) :
     FeatureBase(FEAT_POINT_IMAGE, _measurement,Eigen::MatrixXs::Zero(0,0))
 {
@@ -17,3 +20,5 @@ FeaturePointImage::~FeaturePointImage()
 {
     //
 }
+
+} // namespace wolf
diff --git a/src/feature_point_image.h b/src/feature_point_image.h
index 3dbb8d577..c748353d5 100644
--- a/src/feature_point_image.h
+++ b/src/feature_point_image.h
@@ -8,6 +8,9 @@
 //OpenCV includes
 #include "opencv2/features2d/features2d.hpp"
 
+
+namespace wolf {
+
 /**
  *
  * Test for the feature point
@@ -76,4 +79,7 @@ inline cv::Mat& FeaturePointImage::getDescriptor()
     return descriptor_;
 }
 
+
+} // namespace wolf
+
 #endif // FEATURE_IMAGE_H
diff --git a/src/frame_base.cpp b/src/frame_base.cpp
index 9d5d11d3c..70bd10290 100644
--- a/src/frame_base.cpp
+++ b/src/frame_base.cpp
@@ -5,6 +5,8 @@
 #include "capture_base.h"
 #include "state_block.h"
 
+namespace wolf {
+
 FrameBase::FrameBase(const TimeStamp& _ts, StateBlock* _p_ptr, StateBlock* _o_ptr, StateBlock* _v_ptr) :
             NodeConstrained(MID, "FRAME"),
             type_(NON_KEY_FRAME),
@@ -253,3 +255,5 @@ void FrameBase::setStatus(StateStatus _st)
         }
     }
 }
+
+} // namespace wolf
diff --git a/src/frame_base.h b/src/frame_base.h
index e9b6dcee4..13d4c2a14 100644
--- a/src/frame_base.h
+++ b/src/frame_base.h
@@ -15,6 +15,8 @@ class StateBlock;
 
 //std includes
 
+namespace wolf {
+
 //class FrameBase
 class FrameBase : public NodeConstrained<TrajectoryBase,CaptureBase>
 {
@@ -192,4 +194,6 @@ inline StateStatus FrameBase::getStatus() const
     return status_;
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/hardware_base.cpp b/src/hardware_base.cpp
index acc5971fc..ea70a455b 100644
--- a/src/hardware_base.cpp
+++ b/src/hardware_base.cpp
@@ -2,6 +2,9 @@
 #include "sensor_base.h"
 #include "wolf_problem.h"
 
+
+namespace wolf {
+
 HardwareBase::HardwareBase() :
     NodeLinked(MID, "HARDWARE")
 {
@@ -27,3 +30,5 @@ void HardwareBase::removeSensor(SensorBase* _sensor_ptr)
 {
     removeDownNode(_sensor_ptr->nodeId());
 }
+
+} // namespace wolf
diff --git a/src/hardware_base.h b/src/hardware_base.h
index 6afaae736..ae4ce1915 100644
--- a/src/hardware_base.h
+++ b/src/hardware_base.h
@@ -9,6 +9,8 @@ class WolfProblem;
 #include "wolf.h"
 #include "node_linked.h"
 
+namespace wolf {
+
 //class HardwareBase
 class HardwareBase : public NodeLinked<WolfProblem, SensorBase>
 {
@@ -42,4 +44,6 @@ inline SensorBaseList* HardwareBase::getSensorListPtr()
     return getDownNodeListPtr();
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/landmark_base.cpp b/src/landmark_base.cpp
index 11c16bdd0..3f052b116 100644
--- a/src/landmark_base.cpp
+++ b/src/landmark_base.cpp
@@ -5,6 +5,8 @@
 #include "node_terminus.h"
 #include "state_block.h"
 
+namespace wolf {
+
 LandmarkBase::LandmarkBase(const LandmarkType & _tp, StateBlock* _p_ptr, StateBlock* _o_ptr) :
             NodeConstrained(MID, "LANDMARK"),
             type_(_tp),
@@ -93,3 +95,5 @@ void LandmarkBase::registerNewStateBlocks()
             getWolfProblem()->addStateBlockPtr(o_ptr_);
     }
 }
+
+} // namespace wolf
diff --git a/src/landmark_base.h b/src/landmark_base.h
index 5c67f7052..c8e6b200d 100644
--- a/src/landmark_base.h
+++ b/src/landmark_base.h
@@ -13,6 +13,8 @@ class StateBlock;
 
 //std includes
 
+namespace wolf {
+
 // TODO: add descriptor as a StateBlock -> Could be estimated or not. Aperture could be one case of "descriptor"that can be estimated or not
 // TODO: init and end Time stamps
 
@@ -151,4 +153,5 @@ inline const LandmarkType LandmarkBase::getType() const
     return type_;
 }
 
+} // namespace wolf
 #endif
diff --git a/src/landmark_container.cpp b/src/landmark_container.cpp
index f89170918..3c70c794c 100644
--- a/src/landmark_container.cpp
+++ b/src/landmark_container.cpp
@@ -2,6 +2,8 @@
 #include "landmark_container.h"
 #include "state_block.h"
 
+namespace wolf {
+
 LandmarkContainer::LandmarkContainer(StateBlock* _p_ptr, StateBlock* _o_ptr, const WolfScalar& _witdh, const WolfScalar& _length) :
 	LandmarkBase(LANDMARK_CONTAINER, _p_ptr, _o_ptr),
 	corners_(3,4)
@@ -182,3 +184,5 @@ Eigen::VectorXs LandmarkContainer::getCorner(const unsigned int _id) const
     assert(_id >= 0 && _id <= 4 && "wrong corner id parameter in getCorner(id)");
     return corners_.col(_id);
 }
+
+} // namespace wolf
diff --git a/src/landmark_container.h b/src/landmark_container.h
index 75b90d9a9..02bc307d1 100644
--- a/src/landmark_container.h
+++ b/src/landmark_container.h
@@ -8,6 +8,7 @@
 
 // Std includes
 
+namespace wolf {
 
 //class LandmarkContainer
 class LandmarkContainer : public LandmarkBase
@@ -105,4 +106,7 @@ class LandmarkContainer : public LandmarkBase
         
 };
 
+
+} // namespace wolf
+
 #endif
diff --git a/src/landmark_corner_2D.cpp b/src/landmark_corner_2D.cpp
index ca4b6c85b..f6b32607c 100644
--- a/src/landmark_corner_2D.cpp
+++ b/src/landmark_corner_2D.cpp
@@ -1,6 +1,8 @@
 
 #include "landmark_corner_2D.h"
 
+namespace wolf {
+
 LandmarkCorner2D::LandmarkCorner2D(StateBlock* _p_ptr, StateBlock* _o_ptr, const WolfScalar& _aperture) :
 	LandmarkBase(LANDMARK_CORNER, _p_ptr, _o_ptr)
 {
@@ -17,3 +19,5 @@ WolfScalar LandmarkCorner2D::getAperture() const
 {
     return descriptor_(0);
 }
+
+} // namespace wolf
diff --git a/src/landmark_corner_2D.h b/src/landmark_corner_2D.h
index fe4dbda30..573941bdb 100644
--- a/src/landmark_corner_2D.h
+++ b/src/landmark_corner_2D.h
@@ -9,6 +9,8 @@
 // Std includes
 
 
+namespace wolf {
+
 //class LandmarkCorner2D
 class LandmarkCorner2D : public LandmarkBase
 {
@@ -40,4 +42,7 @@ class LandmarkCorner2D : public LandmarkBase
         WolfScalar getAperture() const;         
         
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/local_parametrization_base.cpp b/src/local_parametrization_base.cpp
index e4a2a6425..7b8552f39 100644
--- a/src/local_parametrization_base.cpp
+++ b/src/local_parametrization_base.cpp
@@ -1,5 +1,8 @@
 #include "local_parametrization_base.h"
 
+
+namespace wolf {
+
 LocalParametrizationBase::LocalParametrizationBase(unsigned int _global_size, unsigned int _local_size) :
         global_size_(_global_size), local_size_(_local_size)
 {
@@ -18,3 +21,5 @@ unsigned int LocalParametrizationBase::getGlobalSize() const
 {
     return global_size_;
 }
+
+} // namespace wolf
diff --git a/src/local_parametrization_base.h b/src/local_parametrization_base.h
index 149e39774..5e1915740 100644
--- a/src/local_parametrization_base.h
+++ b/src/local_parametrization_base.h
@@ -10,6 +10,9 @@
 
 #include "wolf.h"
 
+
+namespace wolf {
+
 class LocalParametrizationBase{
     protected:
         unsigned int global_size_;
@@ -26,4 +29,7 @@ class LocalParametrizationBase{
         unsigned int getLocalSize() const;
         unsigned int getGlobalSize() const;
 };
+
+} // namespace wolf
+
 #endif /* LOCAL_PARAMETRIZATION_BASE_H_ */
diff --git a/src/local_parametrization_homogeneous.cpp b/src/local_parametrization_homogeneous.cpp
index 35e53373f..db5eb4053 100644
--- a/src/local_parametrization_homogeneous.cpp
+++ b/src/local_parametrization_homogeneous.cpp
@@ -7,6 +7,8 @@
 
 #include "local_parametrization_homogeneous.h"
 
+namespace wolf {
+
 LocalParametrizationHomogeneous::LocalParametrizationHomogeneous() :
         LocalParametrizationBase(4, 3)
 {
@@ -60,3 +62,5 @@ bool LocalParametrizationHomogeneous::computeJacobian(const Eigen::Map<const Eig
     _jacobian /= 2;
     return true;
 }
+
+} // namespace wolf
diff --git a/src/local_parametrization_homogeneous.h b/src/local_parametrization_homogeneous.h
index 11e75bd99..6c9626331 100644
--- a/src/local_parametrization_homogeneous.h
+++ b/src/local_parametrization_homogeneous.h
@@ -10,6 +10,9 @@
 
 #include "local_parametrization_base.h"
 
+
+namespace wolf {
+
 /**
  * \brief Local parametrization for homogeneous vectors.
  *
@@ -44,4 +47,6 @@ class LocalParametrizationHomogeneous : public LocalParametrizationBase
         virtual bool computeJacobian(const Eigen::Map<const Eigen::VectorXs>& _h, Eigen::Map<Eigen::MatrixXs>& _jacobian) const;
 };
 
+} // namespace wolf
+
 #endif /* LOCALPARAMETRIZATIONHOMOGENEOUS_H_ */
diff --git a/src/local_parametrization_quaternion.cpp b/src/local_parametrization_quaternion.cpp
index 3f3f88723..f7e6c1f8d 100644
--- a/src/local_parametrization_quaternion.cpp
+++ b/src/local_parametrization_quaternion.cpp
@@ -1,5 +1,7 @@
 #include "local_parametrization_quaternion.h"
 
+namespace wolf {
+
 LocalParametrizationQuaternion::LocalParametrizationQuaternion(QuaternionDeltaReference _delta_ref) :
         LocalParametrizationBase(4, 3),
         delta_reference_(_delta_ref)
@@ -73,3 +75,5 @@ bool LocalParametrizationQuaternion::computeJacobian(const Eigen::Map<const Eige
     }
     return true;
 }
+
+} // namespace wolf
diff --git a/src/local_parametrization_quaternion.h b/src/local_parametrization_quaternion.h
index fa96a1db8..f3c73f895 100644
--- a/src/local_parametrization_quaternion.h
+++ b/src/local_parametrization_quaternion.h
@@ -10,6 +10,9 @@
 
 #include "local_parametrization_base.h"
 
+
+namespace wolf {
+
 /**
   * \brief Local or global orientation error
   *
@@ -58,4 +61,7 @@ class LocalParametrizationQuaternion : public LocalParametrizationBase
                           Eigen::Map<Eigen::VectorXs>& _q_plus_delta_theta) const;
         virtual bool computeJacobian(const Eigen::Map<const Eigen::VectorXs>& _q, Eigen::Map<Eigen::MatrixXs>& _jacobian) const;
 };
+
+} // namespace wolf
+
 #endif /* LOCAL_PARAMETRIZATION_QUATERNION_H_ */
diff --git a/src/map_base.cpp b/src/map_base.cpp
index 67bf1c00d..e6a49a559 100644
--- a/src/map_base.cpp
+++ b/src/map_base.cpp
@@ -2,6 +2,9 @@
 #include "wolf_problem.h"
 #include "landmark_base.h"
 
+
+namespace wolf {
+
 MapBase::MapBase() :
     NodeLinked(MID, "MAP")
 {
@@ -28,3 +31,5 @@ void MapBase::removeLandmark(const LandmarkBaseIter& _landmark_iter)
 {
     removeDownNode(_landmark_iter);
 }
+
+} // namespace wolf
diff --git a/src/map_base.h b/src/map_base.h
index 897977c9d..b93a43f3c 100644
--- a/src/map_base.h
+++ b/src/map_base.h
@@ -12,6 +12,8 @@ class LandmarkBase;
 
 //std includes
 
+namespace wolf {
+
 //class MapBase
 class MapBase : public NodeLinked<WolfProblem,LandmarkBase>
 {
@@ -43,4 +45,6 @@ inline LandmarkBaseList* MapBase::getLandmarkListPtr()
     return getDownNodeListPtr();
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/node_base.cpp b/src/node_base.cpp
index 0c4649bf9..f3e7ac884 100644
--- a/src/node_base.cpp
+++ b/src/node_base.cpp
@@ -1,7 +1,10 @@
 #include "node_base.h"
 #include "wolf_problem.h"
 
+namespace wolf {
+
 //init static node counter
 unsigned int NodeBase::node_id_count_ = 0;
 
 
+} // namespace wolf
diff --git a/src/node_base.h b/src/node_base.h
index 33c38dd32..0e71becf5 100644
--- a/src/node_base.h
+++ b/src/node_base.h
@@ -9,6 +9,9 @@ class WolfProblem;
 
 // std includes
 
+
+namespace wolf {
+
 /** \brief Base class for Nodes
  *
  * Base class for all Nodes in the Wolf tree.
@@ -80,4 +83,6 @@ inline std::string NodeBase::nodeLabel() const
     return label_;
 }
 
+} // namespace wolf
+
 #endif /* NODE_BASE_H_ */
diff --git a/src/node_constrained.h b/src/node_constrained.h
index ba3a03f24..3c759bb8b 100644
--- a/src/node_constrained.h
+++ b/src/node_constrained.h
@@ -10,6 +10,9 @@
 
 #include "node_linked.h"
 
+
+namespace wolf {
+
 /** \brief Base class for nodes receiving Constraints from Features
  * \author jsola
  *
@@ -57,4 +60,6 @@ class NodeConstrained : public NodeLinked<UpperType, LowerType>
 
 };
 
+} // namespace wolf
+
 #endif /* NODE_CONSTRAINED_H_ */
diff --git a/src/node_linked.h b/src/node_linked.h
index 2a6ffdfc9..d0c6e6da3 100644
--- a/src/node_linked.h
+++ b/src/node_linked.h
@@ -17,6 +17,8 @@
 #include "node_base.h"
 #include "wolf.h"
 
+namespace wolf {
+
 /** \brief Linked node element in the Wolf Tree
  * 
  * \param UpperType the type of node one level up in the Wolf tree.
@@ -140,6 +142,7 @@ class NodeLinked : public NodeBase
 
 };
 
+
 //////////////////////////////////////////
 //          IMPLEMENTATION
 //////////////////////////////////////////
@@ -304,6 +307,6 @@ WolfProblem* NodeLinked<UpperType, LowerType>::getWolfProblem()
     return nullptr;
 }
 
-
+} // namespace wolf
 
 #endif /* NODE_LINKED_H_ */
diff --git a/src/node_terminus.h b/src/node_terminus.h
index 90cca9e8d..d40a10610 100644
--- a/src/node_terminus.h
+++ b/src/node_terminus.h
@@ -4,6 +4,8 @@
 //wolf includes
 #include "node_base.h"
 
+namespace wolf {
+
 /**
  * \brief Dummy node to terminate the tree in both the Top and Bottom levels.
  *
@@ -31,4 +33,6 @@ class NodeTerminus : public NodeBase
         }
 };
 
+} // namespace wolf
+
 #endif /* NODE_TERMINUS_H_ */
diff --git a/src/processor_ORB.cpp b/src/processor_ORB.cpp
index 437b74be9..0652e82ca 100644
--- a/src/processor_ORB.cpp
+++ b/src/processor_ORB.cpp
@@ -3,6 +3,8 @@
 
 #include "unistd.h"
 
+namespace wolf {
+
 ProcessorORB::ProcessorORB() : ProcessorTracker(PRC_TRACKER_ORB)
 {
     std::cout << "ProcessorORB constructor" << std::endl;
@@ -23,3 +25,5 @@ void ProcessorORB::establishConstraints(CaptureBase *_capture_ptr)
 {
     //not used yet
 }
+
+} // namespace wolf
diff --git a/src/processor_ORB.h b/src/processor_ORB.h
index 87f403c3e..45ed3e862 100644
--- a/src/processor_ORB.h
+++ b/src/processor_ORB.h
@@ -7,6 +7,8 @@
 
 //#include ORBextractor.h
 
+namespace wolf {
+
 class ProcessorORB : public ProcessorBase
 {
     protected:
@@ -22,4 +24,6 @@ class ProcessorORB : public ProcessorBase
         virtual void establishConstraints(CaptureBase *_capture_ptr);
 };
 
+} // namespace wolf
+
 #endif // PROCESSORORB_H
diff --git a/src/processor_base.cpp b/src/processor_base.cpp
index be9e539f4..6f2b9d8d7 100644
--- a/src/processor_base.cpp
+++ b/src/processor_base.cpp
@@ -2,6 +2,8 @@
 #include "sensor_base.h"
 #include "node_terminus.h"
 
+namespace wolf {
+
 ProcessorBase::ProcessorBase(ProcessorType _tp) :
         NodeLinked(MID, "PROCESSOR"),
         type_(_tp)
@@ -13,3 +15,6 @@ ProcessorBase::~ProcessorBase()
 {
     //
 }
+
+
+} // namespace wolf
diff --git a/src/processor_base.h b/src/processor_base.h
index ec78f2c19..9ca0b80de 100644
--- a/src/processor_base.h
+++ b/src/processor_base.h
@@ -11,6 +11,9 @@ class NodeTerminus;
 
 // Std includes
 
+
+namespace wolf {
+
 //class ProcessorBase
 class ProcessorBase : public NodeLinked<SensorBase, NodeTerminus>
 {
@@ -56,4 +59,6 @@ inline bool ProcessorBase::permittedKeyFrame()
     return getWolfProblem()->permitKeyFrame(this);
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/processor_brisk.cpp b/src/processor_brisk.cpp
index f42250bdb..1b25abaa8 100644
--- a/src/processor_brisk.cpp
+++ b/src/processor_brisk.cpp
@@ -6,6 +6,8 @@
 // other includes
 #include <bitset>
 
+namespace wolf {
+
 /** Public */
 
 /** The "main" class of this processor is "process" */
@@ -361,3 +363,5 @@ unsigned int ProcessorBrisk::track(const FeatureBaseList& _feature_list_in, Feat
 
     return n_last_capture_feat;
 }
+
+} // namespace wolf
diff --git a/src/processor_brisk.h b/src/processor_brisk.h
index 4d821ccc3..c5937a56d 100644
--- a/src/processor_brisk.h
+++ b/src/processor_brisk.h
@@ -19,6 +19,9 @@
 #include <complex>      // std::complex, std::norm
 
 
+
+namespace wolf {
+
 class ProcessorBrisk : public ProcessorTrackerFeature
 {
 protected:
@@ -102,4 +105,6 @@ private:
     virtual unsigned int track(const FeatureBaseList& _feature_list_in, FeatureBaseList & _feature_list_out);
 };
 
+} // namespace wolf
+
 #endif // PROCESSOR_BRISK_H
diff --git a/src/processor_gps.cpp b/src/processor_gps.cpp
index f29e4b4cf..47659402d 100644
--- a/src/processor_gps.cpp
+++ b/src/processor_gps.cpp
@@ -6,6 +6,9 @@
 #include "feature_gps_pseudorange.h"
 #include "constraint_gps_pseudorange_2D.h"
 
+
+namespace wolf {
+
 ProcessorGPS::ProcessorGPS() : ProcessorBase(PRC_GPS_RAW),
         //sensor_gps_ptr_((SensorGPS*)(upperNodePtr())), //TODO here there's a crash. Look at what they'll do in processorLaser and modify as consequence
         capture_gps_ptr_(nullptr)
@@ -53,3 +56,4 @@ void ProcessorGPS::process(CaptureBase* _capture_ptr)
 }
 
 
+} // namespace wolf
diff --git a/src/processor_gps.h b/src/processor_gps.h
index 31b03020a..4d4da359a 100644
--- a/src/processor_gps.h
+++ b/src/processor_gps.h
@@ -14,6 +14,9 @@
 
 // Std includes
 
+
+namespace wolf {
+
 class ProcessorGPS : public ProcessorBase
 {
     protected:
@@ -37,4 +40,6 @@ inline void ProcessorGPS::init(CaptureBase* _capture_ptr)
 {
 }
 
+} // namespace wolf
+
 #endif //WOLF_PROCESSOR_GPS_H
diff --git a/src/processor_laser_2D.cpp b/src/processor_laser_2D.cpp
index c4d5f7827..b54e1f9a7 100644
--- a/src/processor_laser_2D.cpp
+++ b/src/processor_laser_2D.cpp
@@ -1,5 +1,6 @@
 #include "processor_laser_2D.h"
 
+namespace wolf {
 
 ProcessorLaser2D::ProcessorLaser2D() : ProcessorBase(PRC_LIDAR),
         //sensor_laser_ptr_((SensorLaser2D*)(upperNodePtr())), // Static cast to specific sensor at construction time TODO: in construction time upperNodePtr is nullptr, it crashes always, to be removed or changed to somewhere (JVN)
@@ -636,3 +637,5 @@ void ProcessorLaser2D::createContainerLandmark(FeatureCorner2D* _corner_ptr, con
     // Remove corner landmark (it will remove all old constraints)
     getWolfProblem()->getMapPtr()->removeLandmark(_old_corner_landmark_ptr);
 }
+
+} // namespace wolf
diff --git a/src/processor_laser_2D.h b/src/processor_laser_2D.h
index 7072253d6..1a0279279 100644
--- a/src/processor_laser_2D.h
+++ b/src/processor_laser_2D.h
@@ -11,6 +11,8 @@
 
 #include "processor_base.h"
 
+namespace wolf {
+
 //TODO try this, and remove includes below
 //class SensorLaser2D;
 //class CaptureLaser2D;
@@ -99,4 +101,6 @@ inline void ProcessorLaser2D::init(CaptureBase* _origin_ptr)
 {
 }
 
+} // namespace wolf
+
 #endif /* SRC_PROCESSOR_LASER_2D_H_ */
diff --git a/src/processor_motion.cpp b/src/processor_motion.cpp
index c14dd5b28..23481782b 100644
--- a/src/processor_motion.cpp
+++ b/src/processor_motion.cpp
@@ -1,8 +1,13 @@
 /**
- * \file processor_motion2.cpp
+ * \file processor_motion.cpp
  *
  *  Created on: 15/03/2016
  *      \author: jsola
  */
 
+
 #include "processor_motion.h"
+
+namespace wolf {
+
+}
diff --git a/src/processor_motion.h b/src/processor_motion.h
index 94e9158a0..6da6afae7 100644
--- a/src/processor_motion.h
+++ b/src/processor_motion.h
@@ -14,6 +14,7 @@
 #include "time_stamp.h"
 #include "wolf.h"
 
+namespace wolf {
 
 /** \brief class for Motion processors
  * \param MotionDeltaType The type of the motion delta and the motion integrated delta. It can be an Eigen::VectorXs (default) or any other construction, most likely a struct.
@@ -379,4 +380,7 @@ inline typename CaptureMotion2<MotionDeltaType>::MotionBuffer* ProcessorMotion<M
     return last_ptr_->getBufferPtr();
 }
 
+} // namespace wolf
+
+
 #endif /* PROCESSOR_MOTION2_H_ */
diff --git a/src/processor_odom_3D.h b/src/processor_odom_3D.h
index ae8563111..1ebf722f8 100644
--- a/src/processor_odom_3D.h
+++ b/src/processor_odom_3D.h
@@ -10,6 +10,9 @@
 
 #include "processor_motion.h"
 
+
+namespace wolf {
+
 /**\brief The Motion Delta type
  *
  * The motion delta, as a composite struct containing position increment and orientation quaternion increment.
@@ -92,4 +95,6 @@ inline Odom3dDelta ProcessorOdom3d::deltaZero() const
     return Odom3dDelta::Zero(); //  Uses static member function
 }
 
+} // namespace wolf
+
 #endif /* SRC_PROCESSOR_ODOM_3D_H_ */
diff --git a/src/processor_preintegrated_imu.cpp b/src/processor_preintegrated_imu.cpp
index 636a24176..d2b1c8971 100644
--- a/src/processor_preintegrated_imu.cpp
+++ b/src/processor_preintegrated_imu.cpp
@@ -1,5 +1,7 @@
 #include "processor_preintegrated_imu.h"
 
+namespace wolf {
+
 ProcessorPreintegratedIMU::ProcessorPreintegratedIMU(ProcessorType _tp) : ProcessorMotion(_tp)
 {
 }
@@ -8,3 +10,4 @@ ProcessorPreintegratedIMU::~ProcessorPreintegratedIMU()
 {
 }
 
+} // namespace wolf
diff --git a/src/processor_preintegrated_imu.h b/src/processor_preintegrated_imu.h
index fe16bd457..5d635519a 100644
--- a/src/processor_preintegrated_imu.h
+++ b/src/processor_preintegrated_imu.h
@@ -10,6 +10,8 @@
 // STL
 #include <deque>
 
+namespace wolf {
+
 class ProcessorPreintegratedIMU : public ProcessorMotion2{
     public:
         ProcessorPreintegratedIMU(ProcessorType _tp);
@@ -72,4 +74,6 @@ class ProcessorPreintegratedIMU : public ProcessorMotion2{
 
 };
 
+} // namespace wolf
+
 #endif // PROCESSOR_PREINTEGRATED_IMU_H
diff --git a/src/processor_tracker.cpp b/src/processor_tracker.cpp
index 789b9c05d..f1001adf8 100644
--- a/src/processor_tracker.cpp
+++ b/src/processor_tracker.cpp
@@ -7,6 +7,8 @@
 
 #include "processor_tracker.h"
 
+namespace wolf {
+
 ProcessorTracker::ProcessorTracker(ProcessorType _tp) :
     ProcessorBase(_tp),
     origin_ptr_(nullptr),
@@ -22,5 +24,5 @@ ProcessorTracker::~ProcessorTracker()
     // TODO Auto-generated destructor stub
 }
 
-
+} // namespace wolf
 
diff --git a/src/processor_tracker.h b/src/processor_tracker.h
index fa2c62b72..ad6dfa2d1 100644
--- a/src/processor_tracker.h
+++ b/src/processor_tracker.h
@@ -11,6 +11,8 @@
 #include "processor_base.h"
 #include "capture_base.h"
 
+namespace wolf {
+
 class ProcessorTracker : public ProcessorBase
 {
     protected:
@@ -167,4 +169,6 @@ class ProcessorTracker : public ProcessorBase
 
 };
 
+} // namespace wolf
+
 #endif /* SRC_PROCESSOR_TRACKER_H_ */
diff --git a/src/processor_tracker_feature.cpp b/src/processor_tracker_feature.cpp
index 068016c79..9971223d4 100644
--- a/src/processor_tracker_feature.cpp
+++ b/src/processor_tracker_feature.cpp
@@ -7,6 +7,8 @@
 
 #include "processor_tracker_feature.h"
 
+namespace wolf {
+
 ProcessorTrackerFeature::ProcessorTrackerFeature(ProcessorType _tp) :
         ProcessorTracker(_tp)
 {
@@ -53,3 +55,5 @@ unsigned int ProcessorTrackerFeature::processNew()
     // return the number of new features detected in \b last
     return n;
 }
+
+} // namespace wolf
diff --git a/src/processor_tracker_feature.h b/src/processor_tracker_feature.h
index 7bc93cc36..cccb27517 100644
--- a/src/processor_tracker_feature.h
+++ b/src/processor_tracker_feature.h
@@ -11,6 +11,8 @@
 #include "processor_tracker.h"
 #include "capture_base.h"
 
+namespace wolf {
+
 /** \brief General tracker processor
  *
  * This class implements the incremental tracker. It contains three pointers to three Captures of type CaptureBase, named \b origin, \b last and \b incoming:
@@ -113,4 +115,6 @@ class ProcessorTrackerFeature : public ProcessorTracker
         virtual unsigned int processNew();
 };
 
+} // namespace wolf
+
 #endif /* PROCESSOR_TRACKER_FEATURE_H_ */
diff --git a/src/processor_tracker_laser.cpp b/src/processor_tracker_laser.cpp
index 9ca646917..bc33fe88e 100644
--- a/src/processor_tracker_laser.cpp
+++ b/src/processor_tracker_laser.cpp
@@ -1,5 +1,6 @@
 #include "processor_tracker_laser.h"
 
+namespace wolf {
 
 ProcessorTrackerLaser::ProcessorTrackerLaser::ProcessorTrackerLaser() :
         ProcessorTrackerFeature(PRC_TRACKER_LIDAR),
@@ -146,3 +147,5 @@ bool ProcessorTrackerLaser::voteForKeyFrame()
         std::cout << "DON'T VOTE for a new key frame " << std::endl;
     return (incoming_ptr_->getFeatureListPtr()->size() / origin_ptr_->getFeatureListPtr()->size() < min_features_ratio_th_);
 }
+
+} // namespace wolf
diff --git a/src/processor_tracker_laser.h b/src/processor_tracker_laser.h
index a074c34f5..a91ca86c9 100644
--- a/src/processor_tracker_laser.h
+++ b/src/processor_tracker_laser.h
@@ -20,6 +20,9 @@
 #include "laser_scan_utils/corner_detector.h"
 #include "processor_tracker_feature.h"
 
+
+namespace wolf {
+
 //some consts.. TODO: this tuning params should be grouped in a struct and passed to the class from ros node, at constructor level
 const WolfScalar aperture_error_th_ = 20.0*M_PI/180.; //20 degrees
 const WolfScalar angular_error_th_ = 10.0*M_PI/180.; //10 degrees;
@@ -100,4 +103,7 @@ class ProcessorTrackerLaser : public ProcessorTrackerFeature
          */
         virtual bool voteForKeyFrame();
 };
+
+} // namespace wolf
+
 #endif /* SRC_PROCESSOR_TRACKER_LASER_H_ */
diff --git a/src/sensor_base.cpp b/src/sensor_base.cpp
index d08e3b7c4..18e7ac676 100644
--- a/src/sensor_base.cpp
+++ b/src/sensor_base.cpp
@@ -3,6 +3,9 @@
 #include "hardware_base.h"
 #include "processor_base.h"
 
+
+namespace wolf {
+
 SensorBase::SensorBase(const SensorType& _tp, StateBlock* _p_ptr, StateBlock* _o_ptr, StateBlock* _intr_ptr,
                        const unsigned int _noise_size, const bool _extr_dyn) :
         NodeLinked(MID, "SENSOR"),
@@ -107,3 +110,5 @@ void SensorBase::setNoise(const Eigen::VectorXs& _noise_std) {
 	for (unsigned int i=0; i<_noise_std.size(); i++)
 		noise_cov_(i,i) = _noise_std(i) * _noise_std(i);
 }
+
+} // namespace wolf
diff --git a/src/sensor_base.h b/src/sensor_base.h
index 55d1a0df4..b1fa81f0e 100644
--- a/src/sensor_base.h
+++ b/src/sensor_base.h
@@ -12,6 +12,8 @@ class StateBlock;
 
 //std includes
 
+namespace wolf {
+
 class SensorBase : public NodeLinked<HardwareBase, ProcessorBase>
 {
     protected:
@@ -132,4 +134,6 @@ inline Eigen::MatrixXs SensorBase::getNoiseCov()
     return noise_cov_;
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/sensor_camera.cpp b/src/sensor_camera.cpp
index 97eead9f0..2c418c84b 100644
--- a/src/sensor_camera.cpp
+++ b/src/sensor_camera.cpp
@@ -1,5 +1,8 @@
 #include "sensor_camera.h"
 
+
+namespace wolf {
+
 /**
  *
  * Test for the camera sensor
@@ -16,3 +19,5 @@ SensorCamera::~SensorCamera()
 {
     //
 }
+
+} // namespace wolf
diff --git a/src/sensor_camera.h b/src/sensor_camera.h
index 654416b81..573a6d230 100644
--- a/src/sensor_camera.h
+++ b/src/sensor_camera.h
@@ -4,6 +4,9 @@
 //wolf includes
 #include "sensor_base.h"
 
+
+namespace wolf {
+
 /**
  *
  * Test for the camera sensor
@@ -37,4 +40,6 @@ class SensorCamera : public SensorBase
 
 };
 
+} // namespace wolf
+
 #endif // SENSOR_CAMERA_H
diff --git a/src/sensor_gps.cpp b/src/sensor_gps.cpp
index 3972443b4..0fbb2defb 100644
--- a/src/sensor_gps.cpp
+++ b/src/sensor_gps.cpp
@@ -1,6 +1,7 @@
 
 #include "sensor_gps.h"
 
+namespace wolf {
 
 SensorGPS::SensorGPS(StateBlock* _p_ptr, //GPS sensor position with respect to the car frame (base frame)
                      StateBlock* _o_ptr, //GPS sensor orientation with respect to the car frame (base frame)
@@ -51,3 +52,5 @@ void SensorGPS::registerNewStateBlocks()
             getWolfProblem()->addStateBlockPtr(map_o_ptr_);
     }
 }
+
+} // namespace wolf
diff --git a/src/sensor_gps.h b/src/sensor_gps.h
index 981a4a9c7..3d99bbeae 100644
--- a/src/sensor_gps.h
+++ b/src/sensor_gps.h
@@ -13,6 +13,8 @@
 
 // std
 
+namespace wolf {
+
 class SensorGPS : public SensorBase
 {
 protected:
@@ -40,4 +42,7 @@ public:
     virtual void registerNewStateBlocks();
 
 };
+
+} // namespace wolf
+
 #endif //SENSOR_GPS_H_
diff --git a/src/sensor_gps_fix.cpp b/src/sensor_gps_fix.cpp
index 31cc691f9..0b13f59c4 100644
--- a/src/sensor_gps_fix.cpp
+++ b/src/sensor_gps_fix.cpp
@@ -1,5 +1,7 @@
 #include "sensor_gps_fix.h"
 
+namespace wolf {
+
 SensorGPSFix::SensorGPSFix(StateBlock* _p_ptr, StateBlock* _o_ptr, const double& _noise) :
         SensorBase(SEN_GPS_FIX, _p_ptr, _o_ptr, nullptr, Eigen::VectorXs::Constant(1,_noise))
 {
@@ -15,3 +17,6 @@ WolfScalar SensorGPSFix::getNoise() const
 {
     return noise_std_(0);
 }
+
+
+} // namespace wolf
diff --git a/src/sensor_gps_fix.h b/src/sensor_gps_fix.h
index a896c15b9..eccd4ae58 100644
--- a/src/sensor_gps_fix.h
+++ b/src/sensor_gps_fix.h
@@ -7,6 +7,9 @@
 
 // std includes
 
+
+namespace wolf {
+
 class SensorGPSFix : public SensorBase
 {
     public:
@@ -35,4 +38,7 @@ class SensorGPSFix : public SensorBase
         double getNoise() const;
         
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/sensor_imu.cpp b/src/sensor_imu.cpp
index b7082a2e4..91266e407 100644
--- a/src/sensor_imu.cpp
+++ b/src/sensor_imu.cpp
@@ -1,5 +1,7 @@
 #include "sensor_imu.h"
 
+namespace wolf {
+
 SensorOdom2D::SensorOdom2D(StateBlock* _p_ptr, StateBlock* _o_ptr) :
         SensorBase(IMU, _p_ptr, _o_ptr, nullptr, 2)
 {
@@ -10,3 +12,4 @@ SensorOdom2D::~SensorOdom2D()
     //
 }
 
+} // namespace wolf
diff --git a/src/sensor_imu.h b/src/sensor_imu.h
index f6d080dcc..c58a48208 100644
--- a/src/sensor_imu.h
+++ b/src/sensor_imu.h
@@ -4,6 +4,9 @@
 //wolf includes
 #include "sensor_base.h"
 
+
+namespace wolf {
+
 class SensorIMU : public SensorBase
 {
 
@@ -29,4 +32,6 @@ class SensorIMU : public SensorBase
 
 };
 
+} // namespace wolf
+
 #endif // SENSOR_IMU_H
diff --git a/src/sensor_laser_2D.cpp b/src/sensor_laser_2D.cpp
index 9e33f8040..2e6f2aed4 100644
--- a/src/sensor_laser_2D.cpp
+++ b/src/sensor_laser_2D.cpp
@@ -1,5 +1,7 @@
 #include "sensor_laser_2D.h"
 
+namespace wolf {
+
 // SensorLaser2D::SensorLaser2D(const Eigen::VectorXs & _sp, WolfScalar _angle_min, WolfScalar _angle_max, WolfScalar _angle_increment, WolfScalar _range_min, WolfScalar _range_max, WolfScalar _range_stdev, WolfScalar _time_increment, WolfScalar _scan_time) :
 //         SensorBase(LIDAR, _sp, 8)
 // //        SensorBase(LIDAR, _sp,{(WolfScalar)(_nrays), _apert, _rmin, _rmax, _range_stdev})
@@ -141,3 +143,5 @@ void SensorLaser2D::printSensorParameters() const
 //     std::cout << "   time increment: " << getTimeIncrement() << std::endl;
 //     std::cout << "   scan time: " << getScanTime() << std::endl;
 }
+
+} // namespace wolf
diff --git a/src/sensor_laser_2D.h b/src/sensor_laser_2D.h
index 7dff5bcbe..75e9c1f6c 100644
--- a/src/sensor_laser_2D.h
+++ b/src/sensor_laser_2D.h
@@ -10,6 +10,9 @@
 #include "laser_scan_utils/scan_basics.h"
 #include "laser_scan_utils/corner_detector.h"
 
+
+namespace wolf {
+
 class SensorLaser2D : public SensorBase
 {
     protected:
@@ -126,4 +129,8 @@ class SensorLaser2D : public SensorBase
          **/                
         void printSensorParameters() const;
 };
+
+} // namespace wolf
+
+
 #endif /*SENSOR_LASER_2D_H_*/
diff --git a/src/sensor_odom_2D.cpp b/src/sensor_odom_2D.cpp
index 79a70713d..a6560c34e 100644
--- a/src/sensor_odom_2D.cpp
+++ b/src/sensor_odom_2D.cpp
@@ -1,5 +1,7 @@
 #include "sensor_odom_2D.h"
 
+namespace wolf {
+
 SensorOdom2D::SensorOdom2D(StateBlock* _p_ptr, StateBlock* _o_ptr, const WolfScalar& _disp_noise_factor, const WolfScalar&  _rot_noise_factor) :
         SensorBase(SEN_ODOM_2D, _p_ptr, _o_ptr, nullptr, 2), k_disp_to_disp_(_disp_noise_factor), k_rot_to_rot_(_rot_noise_factor)
 {
@@ -19,3 +21,5 @@ WolfScalar SensorOdom2D::getRotVarToRotNoiseFactor() const
 {
     return k_rot_to_rot_;
 }
+
+} // namespace wolf
diff --git a/src/sensor_odom_2D.h b/src/sensor_odom_2D.h
index d0b051933..9edb5150b 100644
--- a/src/sensor_odom_2D.h
+++ b/src/sensor_odom_2D.h
@@ -5,6 +5,8 @@
 //wolf includes
 #include "sensor_base.h"
 
+namespace wolf {
+
 class SensorOdom2D : public SensorBase
 {
 
@@ -46,4 +48,7 @@ class SensorOdom2D : public SensorBase
         double getRotVarToRotNoiseFactor() const;
         
 };
+
+} // namespace wolf
+
 #endif
diff --git a/src/state_block.cpp b/src/state_block.cpp
index 34a7847de..0269d2495 100644
--- a/src/state_block.cpp
+++ b/src/state_block.cpp
@@ -1,2 +1,6 @@
 
 #include "state_block.h"
+
+namespace wolf {
+
+}
diff --git a/src/state_block.h b/src/state_block.h
index 259df6f1a..7f377488c 100644
--- a/src/state_block.h
+++ b/src/state_block.h
@@ -11,6 +11,9 @@ class LocalParametrizationBase;
 //std includes
 #include <iostream>
 
+
+namespace wolf {
+
 /** \brief class StateBlock
  *
  * This class implements a state block for general nonlinear optimization. It offers the following functionality:
@@ -143,4 +146,6 @@ inline LocalParametrizationBase* StateBlock::getLocalParametrizationPtr()
     return local_param_ptr_;
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/state_homogeneous_3d.cpp b/src/state_homogeneous_3d.cpp
index ad3ecfdc4..9946c3122 100644
--- a/src/state_homogeneous_3d.cpp
+++ b/src/state_homogeneous_3d.cpp
@@ -8,6 +8,8 @@
 #include "state_homogeneous_3d.h"
 #include "local_parametrization_homogeneous.h"
 
+namespace wolf {
+
 StateHomogeneous3d::StateHomogeneous3d(const Eigen::VectorXs _state, bool _fixed) :
         StateBlock(_state, _fixed)
 {
@@ -26,3 +28,4 @@ StateHomogeneous3d::~StateHomogeneous3d()
     delete local_param_ptr_;
 }
 
+} // namespace wolf
diff --git a/src/state_homogeneous_3d.h b/src/state_homogeneous_3d.h
index 479345622..c03ffef27 100644
--- a/src/state_homogeneous_3d.h
+++ b/src/state_homogeneous_3d.h
@@ -10,6 +10,8 @@
 
 #include "state_block.h"
 
+namespace wolf {
+
 class StateHomogeneous3d : public StateBlock
 {
     public:
@@ -18,4 +20,6 @@ class StateHomogeneous3d : public StateBlock
         virtual ~StateHomogeneous3d();
 };
 
+} // namespace wolf
+
 #endif /* SRC_STATE_HOMOGENEOUS_3D_H_ */
diff --git a/src/state_quaternion.cpp b/src/state_quaternion.cpp
index 44e2119f7..01d43b4d9 100644
--- a/src/state_quaternion.cpp
+++ b/src/state_quaternion.cpp
@@ -8,6 +8,8 @@
 #include "state_quaternion.h"
 #include "local_parametrization_quaternion.h"
 
+namespace wolf {
+
 StateQuaternion::StateQuaternion(const Eigen::VectorXs _state, bool _fixed) :
         StateBlock(_state, _fixed, new LocalParametrizationQuaternion)
 {
@@ -25,3 +27,4 @@ StateQuaternion::~StateQuaternion()
     delete local_param_ptr_;
 }
 
+} // namespace wolf
diff --git a/src/state_quaternion.h b/src/state_quaternion.h
index 34091ec79..007006b17 100644
--- a/src/state_quaternion.h
+++ b/src/state_quaternion.h
@@ -10,6 +10,8 @@
 
 #include "state_block.h"
 
+namespace wolf {
+
 class StateQuaternion : public StateBlock
 {
     public:
@@ -22,4 +24,6 @@ class StateQuaternion : public StateBlock
         virtual ~StateQuaternion();
 };
 
+} // namespace wolf
+
 #endif /* SRC_STATE_QUATERNION_H_ */
diff --git a/src/tf.h b/src/tf.h
index 3fcbc8251..6a62e54b7 100644
--- a/src/tf.h
+++ b/src/tf.h
@@ -14,6 +14,8 @@
 // Std includes
 #include <eigen3/Eigen/Dense>
 
+namespace wolf {
+
 /**
  * Class for 3D frame transforms.
  *
@@ -129,4 +131,6 @@ class TF
 
 };
 
+} // namespace wolf
+
 #endif /* SRC_TF_H_ */
diff --git a/src/time_stamp.cpp b/src/time_stamp.cpp
index da45cb38e..82b57ef15 100644
--- a/src/time_stamp.cpp
+++ b/src/time_stamp.cpp
@@ -1,6 +1,7 @@
 
 #include "time_stamp.h"
 
+namespace wolf {
 
 TimeStamp::TimeStamp() :
         time_stamp_(0)
@@ -42,3 +43,5 @@ void TimeStamp::print(std::ostream & ost) const
     ost.flags(fmtfl);
     ost.precision(nn);
 }
+
+} // namespace wolf
diff --git a/src/time_stamp.h b/src/time_stamp.h
index 74fac6476..ccadd40fb 100644
--- a/src/time_stamp.h
+++ b/src/time_stamp.h
@@ -12,6 +12,8 @@
 #include <iostream>
 
 
+namespace wolf {
+
 /**
  * \brief TimeStamp implements basic functionalities for time stamps
  * 
@@ -231,4 +233,6 @@ inline TimeStamp TimeStamp::operator +(const WolfScalar& dt)
     return TimeStamp(time_stamp_ + dt);
 }
 
+} // namespace wolf
+
 #endif
diff --git a/src/trajectory_base.cpp b/src/trajectory_base.cpp
index 3c12895dd..babab7748 100644
--- a/src/trajectory_base.cpp
+++ b/src/trajectory_base.cpp
@@ -2,6 +2,7 @@
 #include "frame_base.h"
 #include "wolf_problem.h"
 
+namespace wolf {
 
 TrajectoryBase::TrajectoryBase(FrameStructure _frame_structure) :
     NodeLinked(MID, "TRAJECTORY"),
@@ -27,3 +28,5 @@ void TrajectoryBase::getConstraintList(ConstraintBaseList & _ctr_list)
 	for(auto fr_it = getFrameListPtr()->begin(); fr_it != getFrameListPtr()->end(); ++fr_it)
 		(*fr_it)->getConstraintList(_ctr_list);
 }
+
+} // namespace wolf
diff --git a/src/trajectory_base.h b/src/trajectory_base.h
index 67c0e6c7d..a8d2c3d75 100644
--- a/src/trajectory_base.h
+++ b/src/trajectory_base.h
@@ -12,6 +12,9 @@ class FrameBase;
 
 //std includes
 
+
+namespace wolf {
+
 //class TrajectoryBase
 class TrajectoryBase : public NodeLinked<WolfProblem,FrameBase>
 {
@@ -74,4 +77,7 @@ inline FrameStructure TrajectoryBase::getFrameStructure() const
     return frame_structure_;
 }
 
+
+} // namespace wolf
+
 #endif
diff --git a/src/wolf.h b/src/wolf.h
index 0a83438c7..b367a243c 100644
--- a/src/wolf.h
+++ b/src/wolf.h
@@ -18,6 +18,8 @@
 #include <eigen3/Eigen/Geometry>
 #include <eigen3/Eigen/Sparse>
 
+namespace wolf {
+
 /**
  * \brief scalar type for the Wolf project
  *
@@ -47,6 +49,8 @@ const double MIN_VARIANCE = 1e-6;
 
 }
 
+} // namespace wolf
+
 ///////////////////////////////////////////
 // Construct types for any scalar defined in the typedef WolfScalar above
 ////////////////////////////////////////////
@@ -62,29 +66,31 @@ const double MIN_VARIANCE = 1e-6;
 namespace Eigen  // Eigen namespace extension
 {
 // 1. Vectors and Matrices
-typedef Matrix<WolfScalar, 2, 2, Eigen::RowMajor> Matrix2s;                ///< 2x2 matrix of real WolfScalar type
-typedef Matrix<WolfScalar, 3, 3, Eigen::RowMajor> Matrix3s;                ///< 3x3 matrix of real WolfScalar type
-typedef Matrix<WolfScalar, 4, 4, Eigen::RowMajor> Matrix4s;                ///< 4x4 matrix of real WolfScalar type
-typedef Matrix<WolfScalar, 7, 7, Eigen::RowMajor> Matrix7s;                ///< 7x7 matrix of real WolfScalar type
-typedef Matrix<WolfScalar, Dynamic, Dynamic, Eigen::RowMajor> MatrixXs;    ///< variable size matrix of real WolfScalar type
-typedef Matrix<WolfScalar, 1, 1> Vector1s;                ///< 1-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 2, 1> Vector2s;                ///< 2-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 3, 1> Vector3s;                ///< 3-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 4, 1> Vector4s;                ///< 4-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 6, 1> Vector6s;                ///< 6-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 7, 1> Vector7s;                ///< 7-vector of real WolfScalar type
-typedef Matrix<WolfScalar, Dynamic, 1> VectorXs;          ///< variable size vector of real WolfScalar type
-typedef Matrix<WolfScalar, 1, 2> RowVector2s;             ///< 2-row-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 1, 3> RowVector3s;             ///< 3-row-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 1, 4> RowVector4s;             ///< 4-row-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 1, 7> RowVector7s;             ///< 7-row-vector of real WolfScalar type
-typedef Matrix<WolfScalar, 1, Dynamic> RowVectorXs;       ///< variable size row-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 2, 2, Eigen::RowMajor> Matrix2s;                ///< 2x2 matrix of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 3, 3, Eigen::RowMajor> Matrix3s;                ///< 3x3 matrix of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 4, 4, Eigen::RowMajor> Matrix4s;                ///< 4x4 matrix of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 7, 7, Eigen::RowMajor> Matrix7s;                ///< 7x7 matrix of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, Dynamic, Dynamic, Eigen::RowMajor> MatrixXs;    ///< variable size matrix of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 1, 1> Vector1s;                ///< 1-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 2, 1> Vector2s;                ///< 2-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 3, 1> Vector3s;                ///< 3-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 4, 1> Vector4s;                ///< 4-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 6, 1> Vector6s;                ///< 6-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 7, 1> Vector7s;                ///< 7-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, Dynamic, 1> VectorXs;          ///< variable size vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 1, 2> RowVector2s;             ///< 2-row-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 1, 3> RowVector3s;             ///< 3-row-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 1, 4> RowVector4s;             ///< 4-row-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 1, 7> RowVector7s;             ///< 7-row-vector of real WolfScalar type
+typedef Matrix<wolf::WolfScalar, 1, Dynamic> RowVectorXs;       ///< variable size row-vector of real WolfScalar type
 
 // 2. Quaternions and other rotation things
-typedef Quaternion<WolfScalar> Quaternions;               ///< Quaternion of real WolfScalar type
-typedef AngleAxis<WolfScalar> AngleAxiss;                 ///< Angle-Axis of real WolfScalar type
+typedef Quaternion<wolf::WolfScalar> Quaternions;               ///< Quaternion of real WolfScalar type
+typedef AngleAxis<wolf::WolfScalar> AngleAxiss;                 ///< Angle-Axis of real WolfScalar type
 }
 
+namespace wolf {
+
 /** \brief Enumeration of node locations at Wolf Tree
  *
  * You may add items to this list as needed. Be concise with names, and document your entries.
@@ -333,11 +339,13 @@ inline WolfScalar pi2pi(const WolfScalar& angle)
     return (angle > 0 ? fmod(angle + M_PI, 2 * M_PI) - M_PI : fmod(angle - M_PI, 2 * M_PI) + M_PI);
 }
 
+} // namespace wolf
+
 // Quaternion things
 namespace Eigen{
 inline void v2q(const Eigen::VectorXs& _v, Eigen::Quaternions& _q){
-    WolfScalar angle = _v.norm();
-    if (angle < WolfConstants::EPS)
+    wolf::WolfScalar angle = _v.norm();
+    if (angle < wolf::WolfConstants::EPS)
         _q = Eigen::Quaternions::Identity();
     else
     {
diff --git a/src/wolf_manager.cpp b/src/wolf_manager.cpp
index 4782c062b..94d87b8d6 100644
--- a/src/wolf_manager.cpp
+++ b/src/wolf_manager.cpp
@@ -1,5 +1,8 @@
 #include "wolf_manager.h"
 
+
+namespace wolf {
+
 WolfManager::WolfManager(const FrameStructure _frame_structure,
                          SensorBase* _sensor_prior_ptr,
                          const Eigen::VectorXs& _prior,
@@ -233,3 +236,4 @@ void WolfManager::setNewFrameElapsedTime(const WolfScalar& _dt)
 }
 
 
+} // namespace wolf
diff --git a/src/wolf_manager.h b/src/wolf_manager.h
index 5f038c539..7b1c67030 100644
--- a/src/wolf_manager.h
+++ b/src/wolf_manager.h
@@ -33,6 +33,9 @@
 #include "ceres/ceres.h"
 #include "glog/logging.h"
 
+
+namespace wolf {
+
 class WolfManager
 {
     protected:
@@ -86,3 +89,5 @@ class WolfManager
 
         void setNewFrameElapsedTime(const WolfScalar& _dt);
 };
+
+} // namespace wolf
diff --git a/src/wolf_problem.cpp b/src/wolf_problem.cpp
index be39c2d64..bdf7fb1b1 100644
--- a/src/wolf_problem.cpp
+++ b/src/wolf_problem.cpp
@@ -6,6 +6,9 @@
 #include "trajectory_base.h"
 #include "map_base.h"
 
+
+namespace wolf {
+
 WolfProblem::WolfProblem(FrameStructure _frame_structure) :
         NodeBase("WOLF_PROBLEM"), //
 		location_(TOP),
@@ -231,3 +234,4 @@ void WolfProblem::removeDownNode(const LowerNodePtr _ptr)
     //
 }
 
+} // namespace wolf
diff --git a/src/wolf_problem.h b/src/wolf_problem.h
index a22dca893..63b515d5c 100644
--- a/src/wolf_problem.h
+++ b/src/wolf_problem.h
@@ -14,6 +14,9 @@ class TimeStamp;
 // std includes
 #include <utility> // pair
 
+
+namespace wolf {
+
 /** \brief Wolf problem node element in the Wolf Tree
  * 
  * A node has five main data members:
@@ -248,4 +251,7 @@ inline bool WolfProblem::isTop()
     return true;
 }
 
+} // namespace wolf
+
+
 #endif
-- 
GitLab