Skip to content
Snippets Groups Projects
Commit bfce5c29 authored by Joan Vallvé Navarro's avatar Joan Vallvé Navarro
Browse files

Merge remote-tracking branch 'origin/devel' into...

Merge remote-tracking branch 'origin/devel' into 335-copying-measurement-and-sqrtinfo-in-factorbase-multi-threading
parents bb46bd66 a54c11ad
No related branches found
No related tags found
1 merge request!369Resolve "Copying measurement and sqrtinfo in FactorBase (multi-threading)"
Pipeline #5529 passed
...@@ -443,6 +443,9 @@ ADD_LIBRARY(${PROJECT_NAME} ...@@ -443,6 +443,9 @@ ADD_LIBRARY(${PROJECT_NAME}
${SRCS_WRAPPER} ${SRCS_WRAPPER}
${SRCS_YAML} ${SRCS_YAML}
) )
# Set compiler options
# ====================
if (CMAKE_CXX_COMPILER_ID STREQUAL "Clang") if (CMAKE_CXX_COMPILER_ID STREQUAL "Clang")
message(STATUS "Using C++ compiler clang") message(STATUS "Using C++ compiler clang")
target_compile_options(${PROJECT_NAME} PRIVATE -Winconsistent-missing-override) target_compile_options(${PROJECT_NAME} PRIVATE -Winconsistent-missing-override)
......
...@@ -26,7 +26,7 @@ class SolverManagerDummy : public SolverManager ...@@ -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(); return state_blocks_.find(st)!=state_blocks_.end();
}; };
...@@ -36,7 +36,7 @@ class SolverManagerDummy : public SolverManager ...@@ -36,7 +36,7 @@ class SolverManagerDummy : public SolverManager
return state_block_fixed_.at(st); 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(); return std::find(factors_.begin(), factors_.end(), fac_ptr) != factors_.end();
}; };
...@@ -51,46 +51,46 @@ class SolverManagerDummy : public SolverManager ...@@ -51,46 +51,46 @@ class SolverManagerDummy : public SolverManager
return state_block_local_param_.find(st) != state_block_local_param_.end(); return state_block_local_param_.find(st) != state_block_local_param_.end();
}; };
virtual void computeCovariances(const CovarianceBlocksToBeComputed blocks){}; virtual void computeCovariances(const CovarianceBlocksToBeComputed blocks) override {};
virtual void computeCovariances(const std::vector<StateBlockPtr>& st_list){}; virtual void computeCovariances(const std::vector<StateBlockPtr>& st_list) override {};
virtual bool isStateBlockRegisteredDerived(const StateBlockPtr& state_ptr){return true;}; virtual bool isStateBlockRegisteredDerived(const StateBlockPtr& state_ptr) override {return true;};
virtual bool isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const {return true;}; virtual bool isFactorRegisteredDerived(const FactorBasePtr& fac_ptr) const override {return true;};
// The following are dummy implementations // The following are dummy implementations
bool hasConverged() { return true; } bool hasConverged() override { return true; }
SizeStd iterations() { return 1; } SizeStd iterations() override { return 1; }
double initialCost() { return double(1); } double initialCost() override { return double(1); }
double finalCost() { return double(0); } double finalCost() override { return double(0); }
protected: protected:
virtual bool checkDerived(std::string prefix="") const override {return true;} virtual bool checkDerived(std::string prefix="") const override {return true;}
virtual std::string solveDerived(const ReportVerbosity report_level){ return std::string("");}; virtual std::string solveDerived(const ReportVerbosity report_level) override { return std::string("");};
virtual void addFactorDerived(const FactorBasePtr& fac_ptr) virtual void addFactorDerived(const FactorBasePtr& fac_ptr) override
{ {
factors_.push_back(fac_ptr); factors_.push_back(fac_ptr);
}; };
virtual void removeFactorDerived(const FactorBasePtr& fac_ptr) virtual void removeFactorDerived(const FactorBasePtr& fac_ptr) override
{ {
factors_.remove(fac_ptr); 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_fixed_[state_ptr] = state_ptr->isFixed();
state_block_local_param_[state_ptr] = state_ptr->getLocalParametrization(); 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_fixed_.erase(state_ptr);
state_block_local_param_.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(); 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) if (state_ptr->getLocalParametrization() == nullptr)
state_block_local_param_.erase(state_ptr); state_block_local_param_.erase(state_ptr);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment