diff --git a/test/dummy/solver_manager_dummy.h b/test/dummy/solver_manager_dummy.h index 0e6a1956b97728e8440edca7931c6d5ac32c3bc0..fe62d065c64fbf2f4c37f58b00ff4f51ea2a0ef1 100644 --- a/test/dummy/solver_manager_dummy.h +++ b/test/dummy/solver_manager_dummy.h @@ -26,7 +26,7 @@ class SolverManagerDummy : public SolverManager { }; - bool isStateBlockRegistered(const StateBlockPtr& st) + bool isStateBlockRegistered(const StateBlockPtr& st) override { return state_blocks_.find(st)!=state_blocks_.end(); }; @@ -36,7 +36,7 @@ class SolverManagerDummy : public SolverManager return state_block_fixed_.at(st); }; - bool isFactorRegistered(const FactorBasePtr& fac_ptr) const + bool isFactorRegistered(const FactorBasePtr& fac_ptr) const override { return std::find(factors_.begin(), factors_.end(), fac_ptr) != factors_.end(); }; @@ -51,46 +51,46 @@ class SolverManagerDummy : public SolverManager return state_block_local_param_.find(st) != state_block_local_param_.end(); }; - virtual void computeCovariances(const CovarianceBlocksToBeComputed blocks){}; - virtual void computeCovariances(const std::vector<StateBlockPtr>& st_list){}; - virtual bool isStateBlockRegisteredDerived(const StateBlockPtr& state_ptr){return true;}; - virtual bool isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const {return true;}; + virtual void computeCovariances(const CovarianceBlocksToBeComputed blocks) override {}; + virtual void computeCovariances(const std::vector<StateBlockPtr>& st_list) override {}; + virtual bool isStateBlockRegisteredDerived(const StateBlockPtr& state_ptr) override {return true;}; + virtual bool isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const override {return true;}; // The following are dummy implementations - bool hasConverged() { return true; } - SizeStd iterations() { return 1; } - double initialCost() { return double(1); } - double finalCost() { return double(0); } + bool hasConverged() override { return true; } + SizeStd iterations() override { return 1; } + double initialCost() override { return double(1); } + double finalCost() override { return double(0); } protected: virtual bool checkDerived(std::string prefix="") const override {return true;} - virtual std::string solveDerived(const ReportVerbosity report_level){ return std::string("");}; - virtual void addFactorDerived(const FactorBasePtr& fac_ptr) + virtual std::string solveDerived(const ReportVerbosity report_level) override { return std::string("");}; + virtual void addFactorDerived(const FactorBasePtr& fac_ptr) override { factors_.push_back(fac_ptr); }; - virtual void removeFactorDerived(const FactorBasePtr& fac_ptr) + virtual void removeFactorDerived(const FactorBasePtr& fac_ptr) override { factors_.remove(fac_ptr); }; - virtual void addStateBlockDerived(const StateBlockPtr& state_ptr) + virtual void addStateBlockDerived(const StateBlockPtr& state_ptr) override { state_block_fixed_[state_ptr] = state_ptr->isFixed(); state_block_local_param_[state_ptr] = state_ptr->getLocalParametrization(); }; - virtual void removeStateBlockDerived(const StateBlockPtr& state_ptr) + virtual void removeStateBlockDerived(const StateBlockPtr& state_ptr) override { state_block_fixed_.erase(state_ptr); state_block_local_param_.erase(state_ptr); }; - virtual void updateStateBlockStatusDerived(const StateBlockPtr& state_ptr) + virtual void updateStateBlockStatusDerived(const StateBlockPtr& state_ptr) override { state_block_fixed_[state_ptr] = state_ptr->isFixed(); }; - virtual void updateStateBlockLocalParametrizationDerived(const StateBlockPtr& state_ptr) + virtual void updateStateBlockLocalParametrizationDerived(const StateBlockPtr& state_ptr) override { if (state_ptr->getLocalParametrization() == nullptr) state_block_local_param_.erase(state_ptr);