diff --git a/include/core/capture/capture_base.h b/include/core/capture/capture_base.h index 9597b94c9df780a74798b52be4e470914a1f13ee..68d34c20bfd4e2abe3ca76d331f696d86423effe 100644 --- a/include/core/capture/capture_base.h +++ b/include/core/capture/capture_base.h @@ -118,7 +118,7 @@ class CaptureBase : public NodeBase, public HasStateBlocks, public std::enable_s void removeFeature(FeatureBasePtr _ft_ptr); }; -} // namespace wolf +} #include "core/sensor/sensor_base.h" #include "core/frame/frame_base.h" @@ -128,7 +128,7 @@ class CaptureBase : public NodeBase, public HasStateBlocks, public std::enable_s namespace wolf{ template<typename classType, typename... T> -inline std::shared_ptr<classType> CaptureBase::emplace(FrameBasePtr _frm_ptr, T&&... all) +std::shared_ptr<classType> CaptureBase::emplace(FrameBasePtr _frm_ptr, T&&... all) { std::shared_ptr<classType> cpt = std::make_shared<classType>(std::forward<T>(all)...); cpt->link(_frm_ptr); diff --git a/include/core/capture/capture_motion.h b/include/core/capture/capture_motion.h index b0e13a6adcf7de3293f75dc928850f30939c0695..c0d86ee1089740ecf03b3896f9264cdc2de5db88 100644 --- a/include/core/capture/capture_motion.h +++ b/include/core/capture/capture_motion.h @@ -155,12 +155,12 @@ inline Eigen::MatrixXd CaptureMotion::getJacobianCalib(const TimeStamp& _ts) con return getBuffer().getMotion(_ts).jacobian_calib_; } -inline CaptureBasePtr CaptureMotion::getOriginCapture() +inline wolf::CaptureBasePtr CaptureMotion::getOriginCapture() { return capture_origin_ptr_.lock(); } -inline CaptureBasePtr CaptureMotion::getOriginCapture() const +inline wolf::CaptureBasePtr CaptureMotion::getOriginCapture() const { return capture_origin_ptr_.lock(); } diff --git a/include/core/common/time_stamp.h b/include/core/common/time_stamp.h index f02c16678a761b23940603c4dc63c444fb547c58..2643f13c8f9629dce921726d6dfacf3171c3417f 100644 --- a/include/core/common/time_stamp.h +++ b/include/core/common/time_stamp.h @@ -185,7 +185,7 @@ class TimeStamp }; -inline TimeStamp TimeStamp::Invalid ( ) +inline wolf::TimeStamp TimeStamp::Invalid ( ) { return TimeStamp(-1.0); } diff --git a/include/core/factor/factor_base.h b/include/core/factor/factor_base.h index a1fd254f47684ea688c03c58a4f76c8bc8c31631..e3dd39803de616a707c2d25a21da04bee6bb9e6e 100644 --- a/include/core/factor/factor_base.h +++ b/include/core/factor/factor_base.h @@ -258,7 +258,7 @@ class FactorBase : public NodeBase, public std::enable_shared_from_this<FactorBa namespace wolf{ template<typename classType, typename... T> -inline std::shared_ptr<classType> FactorBase::emplace(FeatureBasePtr _ftr_ptr, T&&... all) +std::shared_ptr<classType> FactorBase::emplace(FeatureBasePtr _ftr_ptr, T&&... all) { std::shared_ptr<classType> ctr = std::make_shared<classType>(std::forward<T>(all)...); ctr->link(_ftr_ptr); diff --git a/include/core/feature/feature_base.h b/include/core/feature/feature_base.h index ff56500d2dfad7bf967c9b37975489afef9f2d5a..43735ff44e297f6e6b71a43122d8e6a71387b340 100644 --- a/include/core/feature/feature_base.h +++ b/include/core/feature/feature_base.h @@ -138,7 +138,7 @@ class FeatureBase : public NodeBase, public std::enable_shared_from_this<Feature virtual void removeConstrainedBy(FactorBasePtr _fac_ptr); }; -} // namespace wolf +} // IMPLEMENTATION @@ -147,7 +147,7 @@ class FeatureBase : public NodeBase, public std::enable_shared_from_this<Feature namespace wolf{ template<typename classType, typename... T> - inline std::shared_ptr<classType> FeatureBase::emplace(CaptureBasePtr _cpt_ptr, T&&... all) + std::shared_ptr<classType> FeatureBase::emplace(CaptureBasePtr _cpt_ptr, T&&... all) { std::shared_ptr<classType> ftr = std::make_shared<classType>(std::forward<T>(all)...); ftr->link(_cpt_ptr); diff --git a/include/core/frame/frame_base.h b/include/core/frame/frame_base.h index 6b93d33d5b832af32fda4e3698e74c6da81e23ea..7234284a5d00ebcb66f6f9a2efee2c38c9745bbd 100644 --- a/include/core/frame/frame_base.h +++ b/include/core/frame/frame_base.h @@ -162,7 +162,7 @@ class FrameBase : public NodeBase, public HasStateBlocks, public std::enable_sha namespace wolf { template<typename classType, typename... T> -inline std::shared_ptr<classType> FrameBase::emplace(TrajectoryBasePtr _ptr, T&&... all) +std::shared_ptr<classType> FrameBase::emplace(TrajectoryBasePtr _ptr, T&&... all) { std::shared_ptr<classType> frm = std::make_shared<classType>(std::forward<T>(all)...); frm->link(_ptr); diff --git a/include/core/landmark/landmark_base.h b/include/core/landmark/landmark_base.h index 82501deadb9b75696997a3693363da8d2105d5f1..21098d33232129521a5d4f56b52db1930feb5eee 100644 --- a/include/core/landmark/landmark_base.h +++ b/include/core/landmark/landmark_base.h @@ -118,7 +118,7 @@ class LandmarkBase : public NodeBase, public HasStateBlocks, public std::enable_ namespace wolf{ template<typename classType, typename... T> -inline std::shared_ptr<classType> LandmarkBase::emplace(MapBasePtr _map_ptr, T&&... all) +std::shared_ptr<classType> LandmarkBase::emplace(MapBasePtr _map_ptr, T&&... all) { std::shared_ptr<classType> lmk = std::make_shared<classType>(std::forward<T>(all)...); lmk->link(_map_ptr); diff --git a/include/core/math/covariance.h b/include/core/math/covariance.h index da6f8b5d1f6b86f098264c8ea0ae29b4ba40fa93..45cbdf3e1366fab06820ca54fad65cfa7e3af5fd 100644 --- a/include/core/math/covariance.h +++ b/include/core/math/covariance.h @@ -14,7 +14,7 @@ namespace wolf{ template <typename T, int N, int RC> inline bool isSymmetric(const Eigen::Matrix<T, N, N, RC>& M, - const T eps = Constants::EPS) + const T eps = wolf::Constants::EPS) { return M.isApprox(M.transpose(), eps); } diff --git a/include/core/math/rotations.h b/include/core/math/rotations.h index c95969f2427d42a0ad968c7810e600d2cfbb25b5..a0a86c6ee4c3ef095725a2df2230c2fdb8de751f 100644 --- a/include/core/math/rotations.h +++ b/include/core/math/rotations.h @@ -263,7 +263,7 @@ exp_q(const Eigen::MatrixBase<Derived>& _v) T angle_squared = _v.squaredNorm(); T angle = sqrt(angle_squared); // Allow ceres::Jet to use its own sqrt() version. - if (angle > (T)(Constants::EPS_SMALL)) + if (angle > (T)(wolf::Constants::EPS_SMALL)) { return Eigen::Quaternion<T> ( Eigen::AngleAxis<T>(angle, _v.normalized()) ); } @@ -295,7 +295,7 @@ log_q(const Eigen::QuaternionBase<Derived>& _q) Eigen::Matrix<T, 3, 1> vec = _q.vec(); const T sin_angle_squared = vec.squaredNorm(); - if (sin_angle_squared > (T)Constants::EPS_SMALL) + if (sin_angle_squared > (T)wolf::Constants::EPS_SMALL) { const T sin_angle = sqrt(sin_angle_squared); // Allow ceres::Jet to use its own sqrt() version. const T& cos_angle = _q.w(); @@ -338,7 +338,7 @@ exp_R(const Eigen::MatrixBase<Derived>& _v) T angle_squared = _v.squaredNorm(); T angle = sqrt(angle_squared); // Allow ceres::Jet to use its own sqrt() version. - if (angle > Constants::EPS_SMALL) + if (angle > wolf::Constants::EPS_SMALL) return Eigen::AngleAxis<T>(angle, _v.normalized()).toRotationMatrix(); else return Eigen::Matrix<T, 3, 3>::Identity() + skew(_v); diff --git a/include/core/problem/problem.h b/include/core/problem/problem.h index bdd307572c1130be139446170244f3a31471a927..3d0eba08b8e234a1adcd3ab4bd00a149e10e6f65 100644 --- a/include/core/problem/problem.h +++ b/include/core/problem/problem.h @@ -451,7 +451,7 @@ inline SizeStd Problem::getStateBlockNotificationMapSize() const return state_block_notification_map_.size(); } -inline SizeStd Problem::getFactorNotificationMapSize() const +inline wolf::SizeStd Problem::getFactorNotificationMapSize() const { std::lock_guard<std::mutex> lock(mut_notifications_); return factor_notification_map_.size(); diff --git a/include/core/processor/factory_processor.h b/include/core/processor/factory_processor.h index 0ca8931266a043783bd98aa4d6c1553805687c30..e36e85a6d109572070bf2d317d81349df73f824a 100644 --- a/include/core/processor/factory_processor.h +++ b/include/core/processor/factory_processor.h @@ -126,7 +126,7 @@ inline std::string FactoryParamsProcessor::getClass() const #define WOLF_REGISTER_PROCESSOR(ProcessorType) \ namespace{ const bool WOLF_UNUSED ProcessorType##Registered = \ - FactoryProcessor::registerCreator(#ProcessorType, ProcessorType::create); } \ + wolf::FactoryProcessor::registerCreator(#ProcessorType, ProcessorType::create); } \ typedef Factory<ProcessorBase, const std::string&, @@ -140,7 +140,7 @@ inline std::string AutoConfFactoryProcessor::getClass() const #define WOLF_REGISTER_PROCESSOR_AUTO(ProcessorType) \ namespace{ const bool WOLF_UNUSED ProcessorType##AutoConfRegistered = \ - AutoConfFactoryProcessor::registerCreator(#ProcessorType, ProcessorType::create); } \ + wolf::AutoConfFactoryProcessor::registerCreator(#ProcessorType, ProcessorType::create); } \ } /* namespace wolf */ diff --git a/include/core/processor/is_motion.h b/include/core/processor/is_motion.h index 8fd67b3462589c7b81211f5311115a863ec68208..a17ac88e7f2d78bc83e5866f10e85173af380638 100644 --- a/include/core/processor/is_motion.h +++ b/include/core/processor/is_motion.h @@ -76,7 +76,7 @@ inline IsMotion::IsMotion(const StateStructure& _structure, ParamsIsMotionPtr _p // } -inline VectorComposite IsMotion::getOdometry ( ) const +inline wolf::VectorComposite IsMotion::getOdometry ( ) const { return odometry_; } diff --git a/include/core/processor/processor_base.h b/include/core/processor/processor_base.h index c43677abe20a7d296d789b9122b4acb2fb072bde..bbb9d109f4ea76919f4c9ddac9c5960eb94de141 100644 --- a/include/core/processor/processor_base.h +++ b/include/core/processor/processor_base.h @@ -457,7 +457,7 @@ inline double ProcessorBase::getTimeTolerance() const } template<typename classType, typename... T> -inline std::shared_ptr<classType> ProcessorBase::emplace(SensorBasePtr _sen_ptr, T&&... all) +std::shared_ptr<classType> ProcessorBase::emplace(SensorBasePtr _sen_ptr, T&&... all) { std::shared_ptr<classType> prc = std::make_shared<classType>(std::forward<T>(all)...); prc->link(_sen_ptr); diff --git a/include/core/processor/processor_diff_drive.h b/include/core/processor/processor_diff_drive.h index feef4a0c2554756e32a2cd9e4d6d59f807a49d6a..7203ff3fd48833c5be92de7445dc174193e6a3e1 100644 --- a/include/core/processor/processor_diff_drive.h +++ b/include/core/processor/processor_diff_drive.h @@ -18,7 +18,7 @@ WOLF_STRUCT_PTR_TYPEDEFS(ParamsProcessorDiffDrive); struct ParamsProcessorDiffDrive : public ParamsProcessorOdom2d { ParamsProcessorDiffDrive() = default; - ParamsProcessorDiffDrive(std::string _unique_name, const ParamsServer & _server) : + ParamsProcessorDiffDrive(std::string _unique_name, const wolf::ParamsServer & _server) : ParamsProcessorOdom2d(_unique_name, _server) { } diff --git a/include/core/processor/processor_fix_wing_model.h b/include/core/processor/processor_fix_wing_model.h index 46be12a4c41a2bcdf6a62c45d645bbb6652a22bd..8c23917354ca1d0e0c3723045ded8d118e3c3abc 100644 --- a/include/core/processor/processor_fix_wing_model.h +++ b/include/core/processor/processor_fix_wing_model.h @@ -22,14 +22,14 @@ struct ParamsProcessorFixWingModel : public ParamsProcessorBase double min_vel_norm; ParamsProcessorFixWingModel() = default; - ParamsProcessorFixWingModel(std::string _unique_name, const ParamsServer & _server) : + ParamsProcessorFixWingModel(std::string _unique_name, const wolf::ParamsServer & _server) : ParamsProcessorBase(_unique_name, _server) { velocity_local = _server.getParam<Eigen::Vector3d> (prefix + _unique_name + "/velocity_local"); angle_stdev = _server.getParam<double> (prefix + _unique_name + "/angle_stdev"); min_vel_norm = _server.getParam<double> (prefix + _unique_name + "/min_vel_norm"); - assert(std::abs(velocity_local.norm() - 1.0) < Constants::EPS && "ParamsProcessorFixWingModel: 'velocity_local' must be normalized"); + assert(std::abs(velocity_local.norm() - 1.0) < wolf::Constants::EPS && "ParamsProcessorFixWingModel: 'velocity_local' must be normalized"); } std::string print() const override { diff --git a/include/core/processor/processor_motion.h b/include/core/processor/processor_motion.h index 1e2cb1a08daa6c910a287a980fec482de9b8435b..207bacb8eb7c9770787e00e9a811b30543708c51 100644 --- a/include/core/processor/processor_motion.h +++ b/include/core/processor/processor_motion.h @@ -250,10 +250,10 @@ class ProcessorMotion : public ProcessorBase, public IsMotion double updateDt(); void integrateOneStep(); void reintegrateBuffer(CaptureMotionPtr _capture_ptr) const; - void splitBuffer(const CaptureMotionPtr& capture_source, + void splitBuffer(const wolf::CaptureMotionPtr& capture_source, TimeStamp ts_split, const FrameBasePtr& keyframe_target, - const CaptureMotionPtr& capture_target) const; + const wolf::CaptureMotionPtr& capture_target) const; /** Pre-process incoming Capture * diff --git a/include/core/processor/processor_odom_2d.h b/include/core/processor/processor_odom_2d.h index 835b026f7a7dc5476e87975a496d7e0b0fa4c1dd..254eded5ccc644faf5b6c20e128f55da77c92b95 100644 --- a/include/core/processor/processor_odom_2d.h +++ b/include/core/processor/processor_odom_2d.h @@ -24,7 +24,7 @@ struct ParamsProcessorOdom2d : public ParamsProcessorMotion double cov_det = 1.0; ParamsProcessorOdom2d() = default; - ParamsProcessorOdom2d(std::string _unique_name, const ParamsServer & _server) : + ParamsProcessorOdom2d(std::string _unique_name, const wolf::ParamsServer & _server) : ParamsProcessorMotion(_unique_name, _server) { cov_det = _server.getParam<double>(prefix + _unique_name + "/keyframe_vote/cov_det"); diff --git a/include/core/processor/processor_tracker.h b/include/core/processor/processor_tracker.h index cfec203bb9cee589fb051105ea7983e084c1af72..855d30ee277a718826870f150d6bc13d789b0931 100644 --- a/include/core/processor/processor_tracker.h +++ b/include/core/processor/processor_tracker.h @@ -21,7 +21,7 @@ struct ParamsProcessorTracker : public ParamsProcessorBase int max_new_features; ///< maximum nbr. of new features to be processed when adding a keyframe (-1: unlimited. 0: none.) ParamsProcessorTracker() = default; - ParamsProcessorTracker(std::string _unique_name, const ParamsServer & _server): + ParamsProcessorTracker(std::string _unique_name, const wolf::ParamsServer & _server): ParamsProcessorBase(_unique_name, _server) { min_features_for_keyframe = _server.getParam<unsigned int>(prefix + _unique_name + "/keyframe_vote/min_features_for_keyframe"); diff --git a/include/core/sensor/sensor_base.h b/include/core/sensor/sensor_base.h index b11d8c61738c968a5e536d0dc644025124e31e31..b80ac75c31d27014cb1affc8d9012e60b6476017 100644 --- a/include/core/sensor/sensor_base.h +++ b/include/core/sensor/sensor_base.h @@ -271,7 +271,7 @@ class SensorBase : public NodeBase, public HasStateBlocks, public std::enable_sh namespace wolf{ template<typename classType, typename... T> -inline std::shared_ptr<classType> SensorBase::emplace(HardwareBasePtr _hwd_ptr, T&&... all) +std::shared_ptr<classType> SensorBase::emplace(HardwareBasePtr _hwd_ptr, T&&... all) { std::shared_ptr<classType> sen = std::make_shared<classType>(std::forward<T>(all)...); sen->link(_hwd_ptr); diff --git a/include/core/sensor/sensor_diff_drive.h b/include/core/sensor/sensor_diff_drive.h index e396a7b5f8017cde4bb7194e818bf18fb796ea1a..212a955b19c1a76aecebaa90f7cc39be73f38a7a 100644 --- a/include/core/sensor/sensor_diff_drive.h +++ b/include/core/sensor/sensor_diff_drive.h @@ -26,7 +26,7 @@ struct ParamsSensorDiffDrive : public ParamsSensorBase double ticks_cov_factor; ParamsSensorDiffDrive() = default; - ParamsSensorDiffDrive(std::string _unique_name, const ParamsServer& _server) + ParamsSensorDiffDrive(std::string _unique_name, const wolf::ParamsServer& _server) : ParamsSensorBase(_unique_name, _server) { radius_left = _server.getParam<double>(prefix + _unique_name + "/radius_left"); @@ -72,7 +72,7 @@ class SensorDiffDrive : public SensorBase }; -inline ParamsSensorDiffDriveConstPtr SensorDiffDrive::getParams() const +inline wolf::ParamsSensorDiffDriveConstPtr SensorDiffDrive::getParams() const { return params_diff_drive_; } diff --git a/include/core/solver/factory_solver.h b/include/core/solver/factory_solver.h index 2a21f66794b048f46ccaf87b641e30cdc255acf2..3e13e598fbd2726532333f2a71d4eabc5adcc1fb 100644 --- a/include/core/solver/factory_solver.h +++ b/include/core/solver/factory_solver.h @@ -37,7 +37,7 @@ inline std::string FactorySolver::getClass() const #define WOLF_REGISTER_SOLVER(SolverType) \ namespace{ const bool WOLF_UNUSED SolverType##Registered = \ - FactorySolver::registerCreator(#SolverType, SolverType::create); } \ + wolf::FactorySolver::registerCreator(#SolverType, SolverType::create); } \ } /* namespace wolf */ diff --git a/include/core/state_block/has_state_blocks.h b/include/core/state_block/has_state_blocks.h index 71ef52dd800b9af25fb4374c3a646bc257468437..418e0909fdfd7e32f42347dee4644cb6eba73c97 100644 --- a/include/core/state_block/has_state_blocks.h +++ b/include/core/state_block/has_state_blocks.h @@ -57,7 +57,7 @@ class HasStateBlocks template<typename ... Args> StateBlockPtr emplaceStateBlock(const char& _sb_type, ProblemPtr _problem, Args&&... _args_of_base_state_block_constructor); - // Register/remove state blocks to/from Problem + // Register/remove state blocks to/from wolf::Problem void registerNewStateBlocks(ProblemPtr _problem) const; void removeStateBlocks(ProblemPtr _problem); @@ -161,7 +161,7 @@ inline bool HasStateBlocks::setStateBlock(const char _sb_type, const StateBlockP return true; // success } -inline StateBlockPtr HasStateBlocks::getStateBlock(const char& _sb_type) const +inline wolf::StateBlockPtr HasStateBlocks::getStateBlock(const char& _sb_type) const { auto it = state_block_map_.find(_sb_type); if (it != state_block_map_.end()) @@ -170,12 +170,12 @@ inline StateBlockPtr HasStateBlocks::getStateBlock(const char& _sb_type) const return nullptr; } -inline StateBlockPtr HasStateBlocks::getP() const +inline wolf::StateBlockPtr HasStateBlocks::getP() const { return getStateBlock('P'); } -inline StateBlockPtr HasStateBlocks::getO() const +inline wolf::StateBlockPtr HasStateBlocks::getO() const { return getStateBlock('O'); } diff --git a/include/core/state_block/state_composite.h b/include/core/state_block/state_composite.h index 7ca4f7d214471b9b5bd530926ed2b5628097c837..0d83c63e531dcdf3f2d8918800d463e3f6a3d2c7 100644 --- a/include/core/state_block/state_composite.h +++ b/include/core/state_block/state_composite.h @@ -56,7 +56,7 @@ class VectorComposite : public std::unordered_map < char, Eigen::VectorXd > * Usage: * * Eigen::VectorXd vec_eigen; - * VectorComposite vec_comp; + * wolf::VectorComposite vec_comp; * * vec_comp.set( vec_eigen, "ab", {2,3} ); // vec_eigen must be at least size 5 !! * @@ -70,10 +70,10 @@ class VectorComposite : public std::unordered_map < char, Eigen::VectorXd > bool includesStructure(const StateStructure &_structure) const; - friend std::ostream& operator <<(std::ostream &_os, const VectorComposite &_x); - friend VectorComposite operator +(const VectorComposite &_x, const VectorComposite &_y); - friend VectorComposite operator -(const VectorComposite &_x, const VectorComposite &_y); - friend VectorComposite operator -(const VectorComposite &_x); + friend std::ostream& operator <<(std::ostream &_os, const wolf::VectorComposite &_x); + friend wolf::VectorComposite operator +(const wolf::VectorComposite &_x, const wolf::VectorComposite &_y); + friend wolf::VectorComposite operator -(const wolf::VectorComposite &_x, const wolf::VectorComposite &_y); + friend wolf::VectorComposite operator -(const wolf::VectorComposite &_x); }; @@ -335,7 +335,7 @@ inline unsigned int MatrixComposite::count(const char &_row, const char &_col) c template<typename SB, typename ... Args> -inline std::shared_ptr<SB> StateBlockComposite::emplace(const char &_sb_type, +inline std::shared_ptr<SB> wolf::StateBlockComposite::emplace(const char &_sb_type, Args &&... _args_of_derived_state_block_constructor) { assert(state_block_map_.count(_sb_type) == 0 && "Trying to add a state block with an existing type! Use setStateBlock instead."); @@ -347,7 +347,7 @@ inline std::shared_ptr<SB> StateBlockComposite::emplace(const char &_sb_type, } template<typename ... Args> -inline StateBlockPtr StateBlockComposite::emplace(const char &_sb_type, +inline StateBlockPtr wolf::StateBlockComposite::emplace(const char &_sb_type, Args &&... _args_of_base_state_block_constructor) { assert(state_block_map_.count(_sb_type) == 0 && "Trying to add a state block with an existing type! Use setStateBlock instead."); diff --git a/include/core/tree_manager/factory_tree_manager.h b/include/core/tree_manager/factory_tree_manager.h index 8de0c48ccd5a5e16cb49abf6b79ae8deffc710c1..c9e91935fe52e08b2ea1bf0c264b5e67ca5ef4e1 100644 --- a/include/core/tree_manager/factory_tree_manager.h +++ b/include/core/tree_manager/factory_tree_manager.h @@ -40,7 +40,7 @@ inline std::string FactoryTreeManager::getClass() const #define WOLF_REGISTER_TREE_MANAGER(TreeManagerType) \ namespace{ const bool WOLF_UNUSED TreeManagerType##Registered = \ - FactoryTreeManager::registerCreator(#TreeManagerType, TreeManagerType::create); } \ + wolf::FactoryTreeManager::registerCreator(#TreeManagerType, TreeManagerType::create); } \ typedef Factory<TreeManagerBase, const std::string&, @@ -54,7 +54,7 @@ inline std::string AutoConfFactoryTreeManager::getClass() const #define WOLF_REGISTER_TREE_MANAGER_AUTO(TreeManagerType) \ namespace{ const bool WOLF_UNUSED TreeManagerType##AutoConfRegistered = \ - AutoConfFactoryTreeManager::registerCreator(#TreeManagerType, TreeManagerType::create); } \ + wolf::AutoConfFactoryTreeManager::registerCreator(#TreeManagerType, TreeManagerType::create); } \ } /* namespace wolf */ diff --git a/include/core/tree_manager/tree_manager_sliding_window.h b/include/core/tree_manager/tree_manager_sliding_window.h index 1cd894c9dc21b8e38078d7fdab7beeb0abfb4093..16e58428dc7fdce89b919e22109a6595dce5afd3 100644 --- a/include/core/tree_manager/tree_manager_sliding_window.h +++ b/include/core/tree_manager/tree_manager_sliding_window.h @@ -12,7 +12,7 @@ WOLF_PTR_TYPEDEFS(TreeManagerSlidingWindow) struct ParamsTreeManagerSlidingWindow : public ParamsTreeManagerBase { ParamsTreeManagerSlidingWindow() = default; - ParamsTreeManagerSlidingWindow(std::string _unique_name, const ParamsServer & _server) : + ParamsTreeManagerSlidingWindow(std::string _unique_name, const wolf::ParamsServer & _server) : ParamsTreeManagerBase(_unique_name, _server) { n_frames = _server.getParam<unsigned int>(prefix + "/n_frames"); diff --git a/include/core/tree_manager/tree_manager_sliding_window_dual_rate.h b/include/core/tree_manager/tree_manager_sliding_window_dual_rate.h index 015a3fce46e632901ae1b2b1e77efd0a526cada4..f0e20f4b5eec08e6f322424f7353ca124b448e90 100644 --- a/include/core/tree_manager/tree_manager_sliding_window_dual_rate.h +++ b/include/core/tree_manager/tree_manager_sliding_window_dual_rate.h @@ -12,7 +12,7 @@ WOLF_PTR_TYPEDEFS(TreeManagerSlidingWindowDualRate) struct ParamsTreeManagerSlidingWindowDualRate : public ParamsTreeManagerSlidingWindow { ParamsTreeManagerSlidingWindowDualRate() = default; - ParamsTreeManagerSlidingWindowDualRate(std::string _unique_name, const ParamsServer & _server) : + ParamsTreeManagerSlidingWindowDualRate(std::string _unique_name, const wolf::ParamsServer & _server) : ParamsTreeManagerSlidingWindow(_unique_name, _server) { n_frames_recent = _server.getParam<unsigned int>(prefix + "/n_frames_recent"); diff --git a/src/processor/is_motion.cpp b/src/processor/is_motion.cpp index 484d083c4294377e9c69a0161a259ff6384d163c..57333a05529ea41f3866cf7c52fb782c695ae3ca 100644 --- a/src/processor/is_motion.cpp +++ b/src/processor/is_motion.cpp @@ -1,9 +1,7 @@ #include "core/processor/is_motion.h" #include "core/problem/problem.h" -//using namespace wolf; - -namespace wolf { +using namespace wolf; void IsMotion::addToProblem(ProblemPtr _prb_ptr, IsMotionPtr _motion_ptr) { @@ -23,5 +21,3 @@ void IsMotion::setOdometry(const VectorComposite& _odom) for (auto key : state_structure_) odometry_[key] = _odom.at(key); //overwrite/insert only keys of the state_structure_ } - -} // namespace wolf