From e750166f3d9da49d8df8b11c162a05d06a21ca6f Mon Sep 17 00:00:00 2001 From: joanvallve <jvallve@iri.upc.edu> Date: Mon, 15 Jun 2020 10:01:21 +0200 Subject: [PATCH] adapted to SolverCeres --- include/node.h | 9 ++------- src/node.cpp | 4 ++-- 2 files changed, 4 insertions(+), 9 deletions(-) diff --git a/include/node.h b/include/node.h index 97d5888..aa55635 100644 --- a/include/node.h +++ b/include/node.h @@ -4,6 +4,7 @@ #include <core/common/node_base.h> #include <core/common/wolf.h> #include <core/capture/capture_odom_2d.h> +#include <core/ceres_wrapper/solver_ceres.h> #include <core/sensor/sensor_odom_2d.h> #include <core/processor/processor_odom_2d.h> #include <core/problem/problem.h> @@ -15,12 +16,6 @@ /************************** * CERES includes * **************************/ -#include "core/ceres_wrapper/ceres_manager.h" -//#include "glog/logging.h" - -/************************** - * ROS includes * - **************************/ #include <ros/ros.h> #include <ros/package.h> #include <nav_msgs/Odometry.h> @@ -70,7 +65,7 @@ class WolfRosNode protected: // solver - SolverManagerPtr solver_manager_ptr_; + SolverManagerPtr solver_; SolverManager::ReportVerbosity solver_verbose_; // transforms diff --git a/src/node.cpp b/src/node.cpp index c7f4da4..dfd0557 100644 --- a/src/node.cpp +++ b/src/node.cpp @@ -38,7 +38,7 @@ WolfRosNode::WolfRosNode() // SOLVER ROS_INFO("Creating solver..."); - solver_manager_ptr_ = std::static_pointer_cast<CeresManager>(FactorySolver::create("CeresManager", problem_ptr_, server)); + solver_ = std::static_pointer_cast<SolverCeres>(FactorySolver::create("SolverCeres", problem_ptr_, server)); int solver_verbose_int; solver_period_ = server.getParam<double>("solver/period"); solver_verbose_int = server.getParam<int>("solver/verbose"); @@ -93,7 +93,7 @@ void WolfRosNode::solve() if (solver_verbose_ != SolverManager::ReportVerbosity::QUIET) ROS_INFO("================ solve =================="); - std::string report = solver_manager_ptr_->solve(solver_verbose_); + std::string report = solver_->solve(solver_verbose_); if (!report.empty()) std::cout << report << std::endl; } -- GitLab