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

use unique_ptr instead of raw ptr

parent 55ef83e9
No related branches found
No related tags found
No related merge requests found
......@@ -22,13 +22,13 @@ CeresManager::CeresManager(ProblemPtr _wolf_problem, const ceres::Solver::Option
covariance_options.num_threads = 8;
covariance_options.apply_loss_function = false;
//covariance_options.null_space_rank = -1;
covariance_ = new ceres::Covariance(covariance_options);
covariance_ = wolf::make_unique<ceres::Covariance>(covariance_options);
ceres::Problem::Options problem_options;
problem_options.cost_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
problem_options.loss_function_ownership = ceres::TAKE_OWNERSHIP;
problem_options.local_parameterization_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
ceres_problem_ = new ceres::Problem(problem_options);
ceres_problem_ = wolf::make_unique<ceres::Problem>(problem_options);
}
CeresManager::~CeresManager()
......@@ -38,11 +38,6 @@ CeresManager::~CeresManager()
while (!ctr_2_residual_idx_.empty())
removeConstraint(ctr_2_residual_idx_.begin()->first);
// std::cout << "all residuals removed! \n";
delete covariance_;
//std::cout << "covariance deleted! \n";
delete ceres_problem_;
//std::cout << "ceres problem deleted! \n";
}
std::string CeresManager::solve(const unsigned int& _report_level)
......@@ -55,7 +50,7 @@ std::string CeresManager::solve(const unsigned int& _report_level)
//std::cout << "After Update: Residual blocks: " << ceres_problem_->NumResidualBlocks() << " Parameter blocks: " << ceres_problem_->NumParameterBlocks() << std::endl;
// run Ceres Solver
ceres::Solve(ceres_options_, ceres_problem_, &summary_);
ceres::Solve(ceres_options_, ceres_problem_.get(), &summary_);
//std::cout << "solved" << std::endl;
//return report
......@@ -190,7 +185,7 @@ void CeresManager::computeCovariances(CovarianceBlocksToBeComputed _blocks)
//std::cout << "pairs... " << double_pairs.size() << std::endl;
// COMPUTE DESIRED COVARIANCES
if (covariance_->Compute(double_pairs, ceres_problem_))
if (covariance_->Compute(double_pairs, ceres_problem_.get()))
{
// STORE DESIRED COVARIANCES
for (unsigned int i = 0; i < double_pairs.size(); i++)
......@@ -230,7 +225,7 @@ void CeresManager::computeCovariances(const StateBlockList& st_list)
//std::cout << "pairs... " << double_pairs.size() << std::endl;
// COMPUTE DESIRED COVARIANCES
if (covariance_->Compute(double_pairs, ceres_problem_))
if (covariance_->Compute(double_pairs, ceres_problem_.get()))
// STORE DESIRED COVARIANCES
for (unsigned int i = 0; i < double_pairs.size(); i++)
{
......
#ifndef CERES_MANAGER_H_
#define CERES_MANAGER_H_
#include "../make_unique.h"
//Ceres includes
#include "ceres/jet.h"
#include "ceres/ceres.h"
......@@ -27,12 +29,14 @@ WOLF_PTR_TYPEDEFS(CeresManager);
class CeresManager : public SolverManager
{
protected:
std::map<ConstraintBasePtr, ceres::ResidualBlockId> ctr_2_residual_idx_;
std::map<ConstraintBasePtr, ceres::CostFunctionPtr> ctr_2_costfunction_;
ceres::Problem* ceres_problem_;
ceres::Solver::Options ceres_options_;
ceres::Covariance* covariance_;
ceres::Solver::Summary summary_;
std::unique_ptr<ceres::Problem> ceres_problem_;
std::unique_ptr<ceres::Covariance> covariance_;
public:
CeresManager(ProblemPtr _wolf_problem, const ceres::Solver::Options& _ceres_options = ceres::Solver::Options());
......
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