Skip to content
Snippets Groups Projects
Commit 6382cffa authored by Jeremie Deray's avatar Jeremie Deray
Browse files

ceres_manager indentation

parent a4d5d353
No related branches found
No related tags found
No related merge requests found
This commit is part of merge request !138. Comments created here will be created in the context of that merge request.
This diff is collapsed.
...@@ -13,7 +13,7 @@ ...@@ -13,7 +13,7 @@
#include "create_numeric_diff_cost_function.h" #include "create_numeric_diff_cost_function.h"
namespace ceres { namespace ceres {
typedef std::shared_ptr<CostFunction> CostFunctionPtr; typedef std::shared_ptr<CostFunction> CostFunctionPtr;
} }
namespace wolf { namespace wolf {
...@@ -26,52 +26,52 @@ WOLF_PTR_TYPEDEFS(CeresManager); ...@@ -26,52 +26,52 @@ WOLF_PTR_TYPEDEFS(CeresManager);
class CeresManager : public SolverManager class CeresManager : public SolverManager
{ {
protected: protected:
std::map<ConstraintBasePtr, ceres::ResidualBlockId> ctr_2_residual_idx_; std::map<ConstraintBasePtr, ceres::ResidualBlockId> ctr_2_residual_idx_;
std::map<ConstraintBasePtr, ceres::CostFunctionPtr> ctr_2_costfunction_; std::map<ConstraintBasePtr, ceres::CostFunctionPtr> ctr_2_costfunction_;
ceres::Problem* ceres_problem_; ceres::Problem* ceres_problem_;
ceres::Solver::Options ceres_options_; ceres::Solver::Options ceres_options_;
ceres::Covariance* covariance_; ceres::Covariance* covariance_;
ceres::Solver::Summary summary_; ceres::Solver::Summary summary_;
public: public:
CeresManager(ProblemPtr _wolf_problem, const ceres::Solver::Options& _ceres_options = ceres::Solver::Options()); CeresManager(ProblemPtr _wolf_problem, const ceres::Solver::Options& _ceres_options = ceres::Solver::Options());
~CeresManager(); ~CeresManager();
virtual std::string solve(const unsigned int& _report_level); virtual std::string solve(const unsigned int& _report_level);
ceres::Solver::Summary getSummary(); ceres::Solver::Summary getSummary();
virtual void computeCovariances(CovarianceBlocksToBeComputed _blocks = ROBOT_LANDMARKS); virtual void computeCovariances(CovarianceBlocksToBeComputed _blocks = ROBOT_LANDMARKS);
virtual void computeCovariances(const StateBlockList& st_list); virtual void computeCovariances(const StateBlockList& st_list);
ceres::Solver::Options& getSolverOptions(); ceres::Solver::Options& getSolverOptions();
private: private:
virtual void addConstraint(ConstraintBasePtr _ctr_ptr); virtual void addConstraint(ConstraintBasePtr _ctr_ptr);
virtual void removeConstraint(ConstraintBasePtr _ctr_ptr); virtual void removeConstraint(ConstraintBasePtr _ctr_ptr);
virtual void addStateBlock(StateBlockPtr _st_ptr); virtual void addStateBlock(StateBlockPtr _st_ptr);
virtual void removeStateBlock(StateBlockPtr _st_ptr); virtual void removeStateBlock(StateBlockPtr _st_ptr);
virtual void updateStateBlockStatus(StateBlockPtr _st_ptr); virtual void updateStateBlockStatus(StateBlockPtr _st_ptr);
ceres::CostFunctionPtr createCostFunction(ConstraintBasePtr _ctr_ptr); ceres::CostFunctionPtr createCostFunction(ConstraintBasePtr _ctr_ptr);
}; };
inline ceres::Solver::Summary CeresManager::getSummary() inline ceres::Solver::Summary CeresManager::getSummary()
{ {
return summary_; return summary_;
} }
inline ceres::Solver::Options& CeresManager::getSolverOptions() inline ceres::Solver::Options& CeresManager::getSolverOptions()
{ {
return ceres_options_; return ceres_options_;
} }
} // namespace wolf } // namespace wolf
......
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