From 6a15a35f60f33fc98a248b6fa9ff646ccaf537e4 Mon Sep 17 00:00:00 2001 From: Rainer Kuemmerle Date: Sat, 2 Dec 2023 12:02:32 +0100 Subject: [PATCH] Drop using __PRETTY_FUNCTION__ --- g2o/apps/g2o_cli/g2o.cpp | 4 +- g2o/apps/g2o_cli/output_helper.cpp | 9 +-- g2o/apps/g2o_simulator/sensor_odometry.h | 3 +- g2o/apps/g2o_simulator/sensor_odometry2d.cpp | 5 +- g2o/apps/g2o_simulator/sensor_odometry3d.cpp | 3 +- g2o/apps/g2o_viewer/main_window.cpp | 2 +- g2o/core/block_solver.hpp | 2 +- g2o/core/cache.cpp | 4 -- g2o/core/hyper_dijkstra.cpp | 9 +-- g2o/core/hyper_graph_action.cpp | 17 ++--- g2o/core/optimizable_graph.cpp | 70 ++++++++----------- g2o/core/optimization_algorithm_dogleg.cpp | 3 +- .../optimization_algorithm_gauss_newton.cpp | 4 +- g2o/core/optimization_algorithm_levenberg.cpp | 14 ++-- g2o/core/parameter_container.cpp | 8 +-- g2o/core/sparse_optimizer.cpp | 14 ++-- g2o/examples/bal/bal_example.cpp | 21 +++--- .../sclam_laser_calib.cpp | 10 +-- .../sclam_odom_laser.cpp | 3 - g2o/examples/data_fitting/circle_fit.cpp | 5 +- g2o/examples/data_fitting/curve_fit.cpp | 5 +- .../g2o_hierarchical/g2o_hierarchical.cpp | 11 +-- .../g2o_incremental/g2o_incremental.cpp | 3 +- .../graph_optimizer_sparse_incremental.cpp | 12 ++-- .../linear_solver_cholmod_online.h | 9 ++- .../g2o_interactive/g2o_online.cpp | 7 +- .../g2o_interactive/g2o_slam_interface.cpp | 4 +- .../g2o_interactive/generate_commands.cpp | 10 +-- .../graph_optimizer_sparse_online.cpp | 7 +- g2o/solvers/csparse/csparse_extension.cpp | 4 +- .../slam2d_linear/solver_slam2d_linear.cpp | 2 +- g2o/stuff/macros.h | 4 -- g2o/stuff/property.cpp | 3 +- g2o/stuff/timeutil.h | 3 +- 34 files changed, 108 insertions(+), 186 deletions(-) diff --git a/g2o/apps/g2o_cli/g2o.cpp b/g2o/apps/g2o_cli/g2o.cpp index cd0b22268..f4a31eca4 100644 --- a/g2o/apps/g2o_cli/g2o.cpp +++ b/g2o/apps/g2o_cli/g2o.cpp @@ -29,7 +29,6 @@ #include #include #include -#include #include #include #include @@ -50,6 +49,7 @@ #include "g2o/stuff/color_macros.h" #include "g2o/stuff/command_args.h" #include "g2o/stuff/filesys_tools.h" +#include "g2o/stuff/logger.h" #include "g2o/stuff/macros.h" #include "g2o/stuff/string_tools.h" #include "g2o/stuff/timeutil.h" @@ -91,7 +91,7 @@ void sigquit_handler(int sig) { hasToStop = 1; static int cnt = 0; if (cnt++ == 2) { - cerr << __PRETTY_FUNCTION__ << " forcing exit" << endl; + G2O_WARN("forcing exit"); exit(1); } } diff --git a/g2o/apps/g2o_cli/output_helper.cpp b/g2o/apps/g2o_cli/output_helper.cpp index 108eed40e..f42cf41b6 100644 --- a/g2o/apps/g2o_cli/output_helper.cpp +++ b/g2o/apps/g2o_cli/output_helper.cpp @@ -28,12 +28,11 @@ #include #include -#include #include "g2o/core/hyper_graph_action.h" #include "g2o/core/optimizable_graph.h" #include "g2o/stuff/filesys_tools.h" -#include "g2o/stuff/string_tools.h" +#include "g2o/stuff/logger.h" using namespace std; namespace g2o { @@ -65,8 +64,7 @@ bool saveGnuplot(const std::string& gnudump, HyperGraphElementAction* saveGnuplot = HyperGraphActionLibrary::instance()->actionByName("writeGnuplot"); if (!saveGnuplot) { - cerr << __PRETTY_FUNCTION__ << ": no action \"writeGnuplot\" registered" - << endl; + G2O_ERROR("no action \"writeGnuplot\" registered"); return false; } WriteGnuplotAction::Parameters params; @@ -187,8 +185,7 @@ bool dumpEdges(std::ostream& os, const OptimizableGraph& optimizer) { HyperGraphElementAction* saveGnuplot = HyperGraphActionLibrary::instance()->actionByName("writeGnuplot"); if (!saveGnuplot) { - cerr << __PRETTY_FUNCTION__ << ": no action \"writeGnuplot\" registered" - << endl; + G2O_ERROR("no action \"writeGnuplot\" registered"); return false; } WriteGnuplotAction::Parameters params; diff --git a/g2o/apps/g2o_simulator/sensor_odometry.h b/g2o/apps/g2o_simulator/sensor_odometry.h index f89d12aa2..77737c757 100644 --- a/g2o/apps/g2o_simulator/sensor_odometry.h +++ b/g2o/apps/g2o_simulator/sensor_odometry.h @@ -27,6 +27,7 @@ #ifndef G2O_ODOMETRY_SENSOR_ #define G2O_ODOMETRY_SENSOR_ +#include "g2o/stuff/logger.h" #include "simulator.h" namespace g2o { @@ -53,7 +54,7 @@ class SensorOdometry : public BinarySensor { ++it; } if (!(pcurr && pprev)) { - cerr << __PRETTY_FUNCTION__ << ": fatal, trajectory empty" << endl; + G2O_ERROR("fatal, trajectory empty"); return; } _robotPoseObject = pprev; diff --git a/g2o/apps/g2o_simulator/sensor_odometry2d.cpp b/g2o/apps/g2o_simulator/sensor_odometry2d.cpp index b923e644a..c04ebc4b6 100644 --- a/g2o/apps/g2o_simulator/sensor_odometry2d.cpp +++ b/g2o/apps/g2o_simulator/sensor_odometry2d.cpp @@ -26,8 +26,7 @@ #include "sensor_odometry2d.h" -#include -#include +#include "g2o/stuff/logger.h" // Robot2D namespace g2o { @@ -53,7 +52,7 @@ void SensorOdometry2D::sense() { ++it; } if (!(pcurr && pprev)) { - cerr << __PRETTY_FUNCTION__ << ": fatal, trajectory empty" << endl; + G2O_ERROR("fatal, trajectory empty"); return; } _robotPoseObject = pprev; diff --git a/g2o/apps/g2o_simulator/sensor_odometry3d.cpp b/g2o/apps/g2o_simulator/sensor_odometry3d.cpp index 5a3ab0a85..db2029b3e 100644 --- a/g2o/apps/g2o_simulator/sensor_odometry3d.cpp +++ b/g2o/apps/g2o_simulator/sensor_odometry3d.cpp @@ -26,6 +26,7 @@ #include "sensor_odometry3d.h" +#include "g2o/stuff/logger.h" #include "g2o/types/slam3d/isometry3d_mappings.h" namespace g2o { @@ -65,7 +66,7 @@ void SensorOdometry3D::sense() { ++it; } if (!(pcurr && pprev)) { - cerr << __PRETTY_FUNCTION__ << ": fatal, trajectory empty" << endl; + G2O_ERROR("fatal, trajectory empty"); return; } _robotPoseObject = pprev; diff --git a/g2o/apps/g2o_viewer/main_window.cpp b/g2o/apps/g2o_viewer/main_window.cpp index 3411db1f0..b731e0772 100644 --- a/g2o/apps/g2o_viewer/main_window.cpp +++ b/g2o/apps/g2o_viewer/main_window.cpp @@ -129,7 +129,7 @@ void MainWindow::on_btnInitialGuess_clicked() { } break; default: - cerr << __PRETTY_FUNCTION__ << " Unknown initialization method" << endl; + cerr << " Unknown initialization method" << endl; break; } diff --git a/g2o/core/block_solver.hpp b/g2o/core/block_solver.hpp index f67d6ea61..730a1a4ba 100644 --- a/g2o/core/block_solver.hpp +++ b/g2o/core/block_solver.hpp @@ -319,7 +319,7 @@ bool BlockSolver::updateStructure( PoseMatrixType* m = _Hpp->block(ind1, ind2, true); e->mapHessianMemory(m->data(), viIdx, vjIdx, transposedBlock); } else { - G2O_ERROR("{}: not supported", __PRETTY_FUNCTION__); + G2O_ERROR("not supported"); } } } diff --git a/g2o/core/cache.cpp b/g2o/core/cache.cpp index 2ab0a2988..49f8eeb48 100644 --- a/g2o/core/cache.cpp +++ b/g2o/core/cache.cpp @@ -26,8 +26,6 @@ #include "cache.h" -#include - #include "factory.h" #include "g2o/stuff/logger.h" #include "optimizable_graph.h" @@ -119,13 +117,11 @@ Cache* CacheContainer::createCache(const Cache::CacheKey& key) { Factory* f = Factory::instance(); HyperGraph::HyperGraphElement* e = f->construct(key.type()); if (!e) { - G2O_ERROR("{}", __PRETTY_FUNCTION__); G2O_ERROR("fatal error in creating cache of type {}", key.type()); return nullptr; } Cache* c = dynamic_cast(e); if (!c) { - G2O_ERROR("{}", __PRETTY_FUNCTION__); G2O_ERROR("fatal error in creating cache of type {}, wrong type", key.type()); return nullptr; diff --git a/g2o/core/hyper_dijkstra.cpp b/g2o/core/hyper_dijkstra.cpp index 2c3b6fcb2..1923cfc20 100644 --- a/g2o/core/hyper_dijkstra.cpp +++ b/g2o/core/hyper_dijkstra.cpp @@ -28,12 +28,9 @@ #include #include -#include #include -#include #include "g2o/stuff/logger.h" -#include "g2o/stuff/macros.h" namespace g2o { @@ -100,8 +97,7 @@ void HyperDijkstra::shortestPaths(HyperGraph::VertexSet& vset, assert(v != 0); AdjacencyMap::iterator it = _adjacencyMap.find(v); if (it == _adjacencyMap.end()) { - G2O_WARN("{} Vertex {} is not in the adjacency map", __PRETTY_FUNCTION__, - v->id()); + G2O_WARN("Vertex {} is not in the adjacency map", v->id()); } assert(it != _adjacencyMap.end()); it->second._distance = 0.; @@ -115,8 +111,7 @@ void HyperDijkstra::shortestPaths(HyperGraph::VertexSet& vset, HyperGraph::Vertex* u = entry.child(); AdjacencyMap::iterator ut = _adjacencyMap.find(u); if (ut == _adjacencyMap.end()) { - G2O_WARN("{} Vertex {} is not in the adjacency map", __PRETTY_FUNCTION__, - u->id()); + G2O_WARN("Vertex {} is not in the adjacency map", u->id()); } assert(ut != _adjacencyMap.end()); double uDistance = ut->second.distance(); diff --git a/g2o/core/hyper_graph_action.cpp b/g2o/core/hyper_graph_action.cpp index 70dd62818..4b3fbd33f 100644 --- a/g2o/core/hyper_graph_action.cpp +++ b/g2o/core/hyper_graph_action.cpp @@ -26,12 +26,10 @@ #include "hyper_graph_action.h" -#include #include #include "cache.h" #include "g2o/stuff/logger.h" -#include "g2o/stuff/macros.h" #include "optimizable_graph.h" namespace g2o { @@ -99,14 +97,13 @@ HyperGraphElementAction* HyperGraphElementActionCollection::operator()( bool HyperGraphElementActionCollection::registerAction( const HyperGraphElementAction::HyperGraphElementActionPtr& action) { #ifdef G2O_DEBUG_ACTIONLIB - G2O_DEBUG("{} {} {}", __PRETTY_FUNCTION__, action->name(), - action->typeName()); + G2O_DEBUG("{} {}", action->name(), action->typeName()); #endif if (action->name() != name()) { G2O_ERROR( - "{}: invalid attempt to register an action in a collection with a " + "invalid attempt to register an action in a collection with a " "different name {} {}", - __PRETTY_FUNCTION__, name(), action->name()); + name(), action->name()); } _actionMap.insert(make_pair(action->typeName(), action)); return true; @@ -152,9 +149,8 @@ bool HyperGraphActionLibrary::registerAction( collection = dynamic_cast(oldAction); if (!collection) { G2O_ERROR( - "{}: : fatal error, a collection is not at the first level in the " - "library", - __PRETTY_FUNCTION__); + "fatal error, a collection is not at the first level in the " + "library"); return false; } } @@ -162,8 +158,7 @@ bool HyperGraphActionLibrary::registerAction( return collection->registerAction(action); } #ifdef G2O_DEBUG_ACTIONLIB - G2O_DEBUG("{}: creating collection for {}", __PRETTY_FUNCTION__, - action->name()); + G2O_DEBUG("creating collection for {}", action->name()); #endif collection = new HyperGraphElementActionCollection(action->name()); _actionMap.insert(make_pair( diff --git a/g2o/core/optimizable_graph.cpp b/g2o/core/optimizable_graph.cpp index 4cf789e3f..7fbbe30d1 100644 --- a/g2o/core/optimizable_graph.cpp +++ b/g2o/core/optimizable_graph.cpp @@ -30,19 +30,14 @@ #include #include #include -#include #include #include #include #include "cache.h" -#include "estimate_propagator.h" #include "factory.h" -#include "g2o/stuff/color_macros.h" #include "g2o/stuff/logger.h" -#include "g2o/stuff/logger_format.h" -#include "g2o/stuff/macros.h" -#include "g2o/stuff/misc.h" +#include "g2o/stuff/logger_format.h" // IWYU pragma: keep #include "g2o/stuff/string_tools.h" #include "hyper_graph_action.h" #include "optimization_algorithm_property.h" @@ -132,7 +127,7 @@ bool OptimizableGraph::Edge::setParameterId(int argNum, int paramId) { bool OptimizableGraph::Edge::resolveParameters() { if (!graph()) { - G2O_ERROR("{}: edge not registered with a graph", __PRETTY_FUNCTION__); + G2O_ERROR("edge not registered with a graph"); return false; } @@ -142,12 +137,11 @@ bool OptimizableGraph::Edge::resolveParameters() { *_parameters[i] = graph()->parameter(index); auto& aux = **_parameters[i]; if (typeid(aux).name() != _parameterTypes[i]) { - G2O_ERROR( - "{}: FATAL, parameter type mismatch - encountered {}; should be {}", - __PRETTY_FUNCTION__, typeid(aux).name(), _parameterTypes[i]); + G2O_CRITICAL("parameter type mismatch - encountered {}; should be {}", + typeid(aux).name(), _parameterTypes[i]); } if (!*_parameters[i]) { - G2O_ERROR("{}: FATAL, *_parameters[i] == 0", __PRETTY_FUNCTION__); + G2O_CRITICAL("*_parameters[i] == 0"); return false; } } @@ -183,25 +177,25 @@ OptimizableGraph::~OptimizableGraph() { bool OptimizableGraph::addVertex(OptimizableGraph::Vertex* ov, Data* userData) { if (ov->id() < 0) { G2O_ERROR( - "{}: FATAL, a vertex with (negative) ID {} cannot be inserted into the " + "FATAL, a vertex with (negative) ID {} cannot be inserted into the " "graph", - __PRETTY_FUNCTION__, ov->id()); + ov->id()); assert(0 && "Invalid vertex id"); return false; } Vertex* inserted = vertex(ov->id()); if (inserted) { G2O_WARN( - "{}: a vertex with ID {} has already been registered with this " + "a vertex with ID {} has already been registered with this " "graph", - __PRETTY_FUNCTION__, ov->id()); + ov->id()); return false; } if (ov->_graph != nullptr && ov->_graph != this) { G2O_ERROR( - "{}: FATAL, vertex with ID {} has already been registered with another " + "FATAL, vertex with ID {} has already been registered with another " "graph {}", - __PRETTY_FUNCTION__, ov->id(), static_cast(ov->_graph)); + ov->id(), static_cast(ov->_graph)); return false; } if (userData) ov->setUserData(userData); @@ -222,9 +216,9 @@ bool OptimizableGraph::addEdge(OptimizableGraph::Edge* e) { if (g != nullptr && g != this) { G2O_ERROR( - "{}: FATAL, edge with ID {} has already registered with another graph " + "FATAL, edge with ID {} has already registered with another graph " "{}", - __PRETTY_FUNCTION__, e->id(), static_cast(g)); + e->id(), static_cast(g)); return false; } @@ -400,7 +394,7 @@ bool OptimizableGraph::load(istream& is) { if (!factory->knowsTag(token)) { if (warnedUnknownTypes.count(token) != 1) { warnedUnknownTypes.insert(token); - G2O_ERROR("{}: Unknown type {}", __PRETTY_FUNCTION__, token); + G2O_ERROR("Unknown type {}", token); } continue; } @@ -417,14 +411,12 @@ bool OptimizableGraph::load(istream& is) { p->setId(pid); bool r = p->read(currentLine); if (!r) { - G2O_ERROR("{}: reading data {} for parameter {} at line ", - __PRETTY_FUNCTION__, pid, lineNumber); + G2O_ERROR("reading data {} for parameter {} at line ", pid, lineNumber); delete p; } else { if (!_parameters.addParameter(p)) { - G2O_ERROR( - "{}: Parameter of type: {} id: {} already defined at line {}", - __PRETTY_FUNCTION__, token, pid, lineNumber); + G2O_ERROR("Parameter of type: {} id: {} already defined at line {}", + token, pid, lineNumber); } } continue; @@ -439,12 +431,12 @@ bool OptimizableGraph::load(istream& is) { currentLine >> id; bool r = v->read(currentLine); if (!r) - G2O_ERROR("{}: Error reading vertex {} {} at line {}", - __PRETTY_FUNCTION__, token, id, lineNumber); + G2O_ERROR("Error reading vertex {} {} at line {}", token, id, + lineNumber); v->setId(id); if (!addVertex(v)) { - G2O_ERROR("{}: Failure adding Vertex {} {} at line {}", - __PRETTY_FUNCTION__, token, id, lineNumber); + G2O_ERROR("Failure adding Vertex {} {} at line {}", token, id, + lineNumber); delete v; } else { previousDataContainer = v; @@ -480,16 +472,15 @@ bool OptimizableGraph::load(istream& is) { } } if (!vertsOkay) { - G2O_ERROR("{}: Unable to find vertices for edge {} at line {} IDs: {}", - __PRETTY_FUNCTION__, token, lineNumber, fmt::join(ids, " ")); + G2O_ERROR("Unable to find vertices for edge {} at line {} IDs: {}", + token, lineNumber, fmt::join(ids, " ")); delete e; e = nullptr; } else { bool r = e->read(currentLine); if (!r || !addEdge(e)) { - G2O_ERROR("{}: Unable to add edge {} at line {} IDs: {}", - __PRETTY_FUNCTION__, token, lineNumber, - fmt::join(ids, " ")); + G2O_ERROR("Unable to add edge {} at line {} IDs: {}", token, + lineNumber, fmt::join(ids, " ")); delete e; e = nullptr; } @@ -501,8 +492,7 @@ bool OptimizableGraph::load(istream& is) { Data* d = static_cast(element); bool r = d->read(currentLine); if (!r) { - G2O_ERROR("{}: Error reading data {} at line {}", __PRETTY_FUNCTION__, - token, lineNumber); + G2O_ERROR("Error reading data {} at line {}", token, lineNumber); delete d; previousData = 0; } else if (previousData) { @@ -515,8 +505,7 @@ bool OptimizableGraph::load(istream& is) { previousData = d; previousDataContainer = 0; } else { - G2O_ERROR("{}: got data element, but no data container available", - __PRETTY_FUNCTION__); + G2O_ERROR("got data element, but no data container available"); delete d; previousData = 0; } @@ -631,14 +620,13 @@ void OptimizableGraph::setRenamedTypesFromString(const std::string& types) { for (size_t i = 0; i < typesMap.size(); ++i) { vector m = strSplit(typesMap[i], "="); if (m.size() != 2) { - G2O_ERROR("{}: unable to extract type map from {}", __PRETTY_FUNCTION__, - typesMap[i]); + G2O_ERROR("unable to extract type map from {}", typesMap[i]); continue; } string typeInFile = trim(m[0]); string loadedType = trim(m[1]); if (!factory->knowsTag(loadedType)) { - G2O_ERROR("{}: unknown type {}", __PRETTY_FUNCTION__, loadedType); + G2O_ERROR("unknown type {}", loadedType); continue; } diff --git a/g2o/core/optimization_algorithm_dogleg.cpp b/g2o/core/optimization_algorithm_dogleg.cpp index 06d47e8f6..2e6d2673c 100644 --- a/g2o/core/optimization_algorithm_dogleg.cpp +++ b/g2o/core/optimization_algorithm_dogleg.cpp @@ -27,7 +27,6 @@ #include "optimization_algorithm_dogleg.h" #include -#include #include "batch_stats.h" #include "block_solver.h" @@ -72,7 +71,7 @@ OptimizationAlgorithm::SolverResult OptimizationAlgorithmDogleg::solve( !online) { // built up the CCS structure, here due to easy time measure bool ok = _solver.buildStructure(); if (!ok) { - G2O_WARN("{}: Failure while building CCS structure", __PRETTY_FUNCTION__); + G2O_WARN("Failure while building CCS structure"); return OptimizationAlgorithm::Fail; } diff --git a/g2o/core/optimization_algorithm_gauss_newton.cpp b/g2o/core/optimization_algorithm_gauss_newton.cpp index 594ad4792..75ca7f250 100644 --- a/g2o/core/optimization_algorithm_gauss_newton.cpp +++ b/g2o/core/optimization_algorithm_gauss_newton.cpp @@ -27,11 +27,9 @@ #include "optimization_algorithm_gauss_newton.h" #include -#include #include "batch_stats.h" #include "g2o/stuff/logger.h" -#include "g2o/stuff/macros.h" #include "g2o/stuff/timeutil.h" #include "solver.h" #include "sparse_optimizer.h" @@ -66,7 +64,7 @@ OptimizationAlgorithm::SolverResult OptimizationAlgorithmGaussNewton::solve( !online) { // built up the CCS structure, here due to easy time measure ok = _solver.buildStructure(); if (!ok) { - G2O_WARN("{}: Failure while building CCS structure", __PRETTY_FUNCTION__); + G2O_WARN("Failure while building CCS structure"); return OptimizationAlgorithm::Fail; } } diff --git a/g2o/core/optimization_algorithm_levenberg.cpp b/g2o/core/optimization_algorithm_levenberg.cpp index 92745f8fa..efa5bae61 100644 --- a/g2o/core/optimization_algorithm_levenberg.cpp +++ b/g2o/core/optimization_algorithm_levenberg.cpp @@ -42,11 +42,11 @@ namespace g2o { OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg( std::unique_ptr solver) : OptimizationAlgorithmWithHessian(*solver.get()), - _currentLambda(cst(-1.)), - _tau(cst(1e-5)), - _goodStepLowerScale(cst(1. / 3.)), - _goodStepUpperScale(cst(2. / 3.)), - _ni(cst(2.)), + _currentLambda(-1), + _tau(1e5), + _goodStepLowerScale(1. / 3.), + _goodStepUpperScale(2. / 3.), + _ni(2.), _levenbergIterations(0), m_solver{std::move(solver)} { _userLambdaInit = @@ -67,7 +67,7 @@ OptimizationAlgorithm::SolverResult OptimizationAlgorithmLevenberg::solve( !online) { // built up the CCS structure, here due to easy time measure bool ok = _solver.buildStructure(); if (!ok) { - G2O_WARN("{}: Failure while building CCS structure", __PRETTY_FUNCTION__); + G2O_WARN("Failure while building CCS structure"); return OptimizationAlgorithm::Fail; } } @@ -124,7 +124,7 @@ OptimizationAlgorithm::SolverResult OptimizationAlgorithmLevenberg::solve( rho = (currentChi - tempChi); double scale = - ok2 ? computeScale() + cst(1e-3) : 1; // make sure it's non-zero :) + ok2 ? computeScale() + 1e-3 : 1; // make sure it's non-zero :) rho /= scale; if (rho > 0 && std::isfinite(tempChi) && ok2) { // last step was good diff --git a/g2o/core/parameter_container.cpp b/g2o/core/parameter_container.cpp index 669daf6a2..fa424b242 100644 --- a/g2o/core/parameter_container.cpp +++ b/g2o/core/parameter_container.cpp @@ -30,9 +30,7 @@ #include #include "factory.h" -#include "g2o/stuff/color_macros.h" #include "g2o/stuff/logger.h" -#include "g2o/stuff/macros.h" #include "g2o/stuff/string_tools.h" #include "parameter.h" @@ -128,13 +126,11 @@ bool ParameterContainer::read( p->setId(pid); bool r = p->read(currentLine); if (!r) { - G2O_ERROR("{}: Error reading data {} for parameter {}", - __PRETTY_FUNCTION__, token, pid); + G2O_ERROR("Error reading data {} for parameter {}", token, pid); delete p; } else { if (!addParameter(p)) { - G2O_ERROR("{}: Parameter of type: {} id: {} already defined", - __PRETTY_FUNCTION__, token, pid); + G2O_ERROR("Parameter of type: {} id: {} already defined", token, pid); } } } // while read line diff --git a/g2o/core/sparse_optimizer.cpp b/g2o/core/sparse_optimizer.cpp index 80cb41e0b..31981368a 100644 --- a/g2o/core/sparse_optimizer.cpp +++ b/g2o/core/sparse_optimizer.cpp @@ -268,8 +268,7 @@ bool SparseOptimizer::initializeOptimization(HyperGraph::VertexSet& vset, int k; bool hasNan = arrayHasNaN(estimateData.data(), estimateDim, &k); if (hasNan) - G2O_WARN("{}: Vertex {} contains a nan entry at index {}", - __PRETTY_FUNCTION__, v->id(), k); + G2O_WARN("Vertex {} contains a nan entry at index {}", v->id(), k); } } #endif @@ -394,9 +393,8 @@ void SparseOptimizer::computeInitialGuess( int SparseOptimizer::optimize(int iterations, bool online) { if (_ivMap.size() == 0) { G2O_WARN( - "{}: 0 vertices to optimize, maybe forgot to call " - "initializeOptimization()", - __PRETTY_FUNCTION__); + "0 vertices to optimize, maybe forgot to call " + "initializeOptimization()"); return -1; } @@ -406,7 +404,7 @@ int SparseOptimizer::optimize(int iterations, bool online) { ok = _algorithm->init(online); if (!ok) { - G2O_ERROR("{}: Error while initializing", __PRETTY_FUNCTION__); + G2O_ERROR("Error while initializing"); return -1; } @@ -462,9 +460,7 @@ void SparseOptimizer::update(const double* update) { OptimizableGraph::Vertex* v = _ivMap[i]; #ifndef NDEBUG bool hasNan = arrayHasNaN(update, v->dimension()); - if (hasNan) - G2O_WARN("{}: Update contains a nan for vertex {}", __PRETTY_FUNCTION__, - v->id()); + if (hasNan) G2O_WARN("Update contains a nan for vertex {}", v->id()); #endif v->oplus(update); update += v->dimension(); diff --git a/g2o/examples/bal/bal_example.cpp b/g2o/examples/bal/bal_example.cpp index e40deb553..863c79fdc 100644 --- a/g2o/examples/bal/bal_example.cpp +++ b/g2o/examples/bal/bal_example.cpp @@ -41,6 +41,7 @@ #include "g2o/core/sparse_optimizer.h" #include "g2o/solvers/pcg/linear_solver_pcg.h" #include "g2o/stuff/command_args.h" +#include "g2o/stuff/logger.h" #if defined G2O_HAVE_CHOLMOD #include "g2o/solvers/cholmod/linear_solver_cholmod.h" @@ -72,18 +73,16 @@ class VertexCameraBAL : public g2o::BaseVertex<9, g2o::bal::Vector9> { VertexCameraBAL() {} bool read(std::istream& /*is*/) override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; + G2O_ERROR("not implemented yet"); return false; } bool write(std::ostream& /*os*/) const override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; + G2O_ERROR("not implemented yet"); return false; } - void setToOriginImpl() override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; - } + void setToOriginImpl() override { G2O_ERROR("not implemented yet"); } void oplusImpl(const double* update) override { g2o::bal::Vector9::ConstMapType v(update, VertexCameraBAL::Dimension); @@ -102,18 +101,16 @@ class VertexPointBAL : public g2o::BaseVertex<3, g2o::Vector3> { VertexPointBAL() {} bool read(std::istream& /*is*/) override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; + G2O_ERROR("not implemented yet"); return false; } bool write(std::ostream& /*os*/) const override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; + G2O_ERROR("not implemented yet"); return false; } - void setToOriginImpl() override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; - } + void setToOriginImpl() override { G2O_ERROR("not implemented yet"); } void oplusImpl(const double* update) override { g2o::Vector3::ConstMapType v(update); @@ -150,11 +147,11 @@ class EdgeObservationBAL EIGEN_MAKE_ALIGNED_OPERATOR_NEW; EdgeObservationBAL() {} bool read(std::istream& /*is*/) override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; + G2O_ERROR("not implemented yet"); return false; } bool write(std::ostream& /*os*/) const override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; + G2O_ERROR("not implemented yet"); return false; } diff --git a/g2o/examples/calibration_odom_laser/sclam_laser_calib.cpp b/g2o/examples/calibration_odom_laser/sclam_laser_calib.cpp index f1f356005..4ada60730 100644 --- a/g2o/examples/calibration_odom_laser/sclam_laser_calib.cpp +++ b/g2o/examples/calibration_odom_laser/sclam_laser_calib.cpp @@ -27,7 +27,6 @@ #include #include #include -#include #include "g2o/core/factory.h" #include "g2o/core/hyper_dijkstra.h" @@ -35,12 +34,9 @@ #include "g2o/core/sparse_optimizer.h" #include "g2o/stuff/color_macros.h" #include "g2o/stuff/command_args.h" -#include "g2o/stuff/filesys_tools.h" +#include "g2o/stuff/logger.h" #include "g2o/stuff/macros.h" -#include "g2o/stuff/string_tools.h" -#include "g2o/stuff/timeutil.h" -#include "g2o/types/data/types_data.h" -#include "g2o/types/sclam2d/types_sclam2d.h" +#include "g2o/types/slam2d/vertex_se2.h" #include "gm2dl_io.h" using namespace std; @@ -56,7 +52,7 @@ void sigquit_handler(int sig) { hasToStop = 1; static int cnt = 0; if (cnt++ == 2) { - cerr << __PRETTY_FUNCTION__ << " forcing exit" << endl; + G2O_WARN("forcing exit"); exit(1); } } diff --git a/g2o/examples/calibration_odom_laser/sclam_odom_laser.cpp b/g2o/examples/calibration_odom_laser/sclam_odom_laser.cpp index f7bb2495e..c22b6587a 100644 --- a/g2o/examples/calibration_odom_laser/sclam_odom_laser.cpp +++ b/g2o/examples/calibration_odom_laser/sclam_odom_laser.cpp @@ -34,10 +34,7 @@ #include "g2o/core/sparse_optimizer.h" #include "g2o/stuff/color_macros.h" #include "g2o/stuff/command_args.h" -#include "g2o/stuff/filesys_tools.h" #include "g2o/stuff/macros.h" -#include "g2o/stuff/string_tools.h" -#include "g2o/stuff/timeutil.h" #include "g2o/types/data/data_queue.h" #include "g2o/types/data/robot_laser.h" #include "g2o/types/sclam2d/odometry_measurement.h" diff --git a/g2o/examples/data_fitting/circle_fit.cpp b/g2o/examples/data_fitting/circle_fit.cpp index 386ed33da..5d95f2dd7 100644 --- a/g2o/examples/data_fitting/circle_fit.cpp +++ b/g2o/examples/data_fitting/circle_fit.cpp @@ -34,6 +34,7 @@ #include "g2o/core/optimization_algorithm_factory.h" #include "g2o/core/sparse_optimizer.h" #include "g2o/stuff/command_args.h" +#include "g2o/stuff/logger.h" #include "g2o/stuff/sampler.h" using namespace std; @@ -64,9 +65,7 @@ class VertexCircle : public g2o::BaseVertex<3, Eigen::Vector3d> { bool write(std::ostream& /*os*/) const override { return false; } - void setToOriginImpl() override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; - } + void setToOriginImpl() override { G2O_ERROR("not implemented yet"); } void oplusImpl(const double* update) override { Eigen::Vector3d::ConstMapType v(update); diff --git a/g2o/examples/data_fitting/curve_fit.cpp b/g2o/examples/data_fitting/curve_fit.cpp index cc38c3ff2..b252b8859 100644 --- a/g2o/examples/data_fitting/curve_fit.cpp +++ b/g2o/examples/data_fitting/curve_fit.cpp @@ -33,6 +33,7 @@ #include "g2o/core/optimization_algorithm_factory.h" #include "g2o/core/sparse_optimizer.h" #include "g2o/stuff/command_args.h" +#include "g2o/stuff/logger.h" #include "g2o/stuff/sampler.h" using namespace std; @@ -72,11 +73,11 @@ class EdgePointOnCurve EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgePointOnCurve() {} bool read(std::istream& /*is*/) override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; + G2O_ERROR("not implemented yet"); return false; } bool write(std::ostream& /*os*/) const override { - cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl; + G2O_ERROR("not implemented yet"); return false; } diff --git a/g2o/examples/g2o_hierarchical/g2o_hierarchical.cpp b/g2o/examples/g2o_hierarchical/g2o_hierarchical.cpp index d21425212..0a3a8adff 100644 --- a/g2o/examples/g2o_hierarchical/g2o_hierarchical.cpp +++ b/g2o/examples/g2o_hierarchical/g2o_hierarchical.cpp @@ -26,11 +26,7 @@ #include -#include -#include #include -#include -#include #include #include @@ -40,7 +36,6 @@ #include "g2o/apps/g2o_cli/dl_wrapper.h" #include "g2o/apps/g2o_cli/g2o_common.h" #include "g2o/apps/g2o_cli/output_helper.h" -#include "g2o/core/estimate_propagator.h" #include "g2o/core/factory.h" #include "g2o/core/hyper_dijkstra.h" #include "g2o/core/optimization_algorithm_factory.h" @@ -49,10 +44,8 @@ #include "g2o/core/sparse_optimizer.h" #include "g2o/stuff/color_macros.h" #include "g2o/stuff/command_args.h" -#include "g2o/stuff/filesys_tools.h" +#include "g2o/stuff/logger.h" #include "g2o/stuff/macros.h" -#include "g2o/stuff/string_tools.h" -#include "g2o/stuff/timeutil.h" #include "star.h" // #include "backbone_tree_action.h" #include "g2o/types/slam3d/parameter_camera.h" @@ -72,7 +65,7 @@ void sigquit_handler(int sig) { hasToStop = 1; static int cnt = 0; if (cnt++ == 2) { - cerr << __PRETTY_FUNCTION__ << " forcing exit" << endl; + G2O_WARN("forcing exit"); exit(1); } } diff --git a/g2o/examples/interactive_slam/g2o_incremental/g2o_incremental.cpp b/g2o/examples/interactive_slam/g2o_incremental/g2o_incremental.cpp index 840590cff..eee0bd543 100644 --- a/g2o/examples/interactive_slam/g2o_incremental/g2o_incremental.cpp +++ b/g2o/examples/interactive_slam/g2o_incremental/g2o_incremental.cpp @@ -20,7 +20,6 @@ #include "g2o/examples/interactive_slam/g2o_interactive/g2o_slam_interface.h" #include "g2o/stuff/command_args.h" -#include "g2o/stuff/macros.h" #include "g2o/stuff/string_tools.h" #include "g2o/stuff/tictoc.h" #include "graph_optimizer_sparse_incremental.h" @@ -77,7 +76,7 @@ void sigquit_handler(int sig) { hasToStop = 1; static int cnt = 0; if (cnt++ == 2) { - cerr << __PRETTY_FUNCTION__ << " forcing exit" << endl; + G2O_WARN("forcing exit"); exit(1); } } diff --git a/g2o/examples/interactive_slam/g2o_incremental/graph_optimizer_sparse_incremental.cpp b/g2o/examples/interactive_slam/g2o_incremental/graph_optimizer_sparse_incremental.cpp index 99a55de01..b1b492514 100644 --- a/g2o/examples/interactive_slam/g2o_incremental/graph_optimizer_sparse_incremental.cpp +++ b/g2o/examples/interactive_slam/g2o_incremental/graph_optimizer_sparse_incremental.cpp @@ -22,6 +22,7 @@ #include "g2o/core/optimization_algorithm_gauss_newton.h" #include "g2o/examples/interactive_slam/g2o_interactive/types_slam2d_online.h" #include "g2o/examples/interactive_slam/g2o_interactive/types_slam3d_online.h" +#include "g2o/stuff/logger.h" #include "g2o/stuff/macros.h" using namespace std; @@ -98,8 +99,7 @@ int SparseOptimizerIncremental::optimize(int iterations, bool online) { if (!online) { ok = _underlyingSolver->buildStructure(); if (!ok) { - cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" - << endl; + G2O_ERROR("Failure while building CCS structure"); return 0; } } @@ -408,8 +408,7 @@ bool SparseOptimizerIncremental::computeCholeskyUpdate() { size_t n = A.cols(); if (_cholmodSparse->columnsAllocated < n) { - // std::cerr << __PRETTY_FUNCTION__ << ": reallocating columns" << - // std::endl; + G2O_DEBUG("reallocating columns"); _cholmodSparse->columnsAllocated = _cholmodSparse->columnsAllocated == 0 ? n @@ -419,8 +418,7 @@ bool SparseOptimizerIncremental::computeCholeskyUpdate() { } size_t nzmax = A.nonZeros(); if (_cholmodSparse->nzmax < nzmax) { - // std::cerr << __PRETTY_FUNCTION__ << ": reallocating row + values" << - // std::endl; + G2O_DEBUG("reallocating row + values"); _cholmodSparse->nzmax = _cholmodSparse->nzmax == 0 ? nzmax @@ -483,7 +481,7 @@ static OptimizationAlgorithm* createSolver(const std::string& solverName) { } bool SparseOptimizerIncremental::initSolver(int dimension, int batchEveryN) { - // cerr << __PRETTY_FUNCTION__ << endl; + G2O_TRACE("init solver"); slamDimension = dimension; if (dimension == 3) { setAlgorithm(createSolver("fix3_2_cholmod")); diff --git a/g2o/examples/interactive_slam/g2o_incremental/linear_solver_cholmod_online.h b/g2o/examples/interactive_slam/g2o_incremental/linear_solver_cholmod_online.h index e5a9a3855..4b4d5be9f 100644 --- a/g2o/examples/interactive_slam/g2o_incremental/linear_solver_cholmod_online.h +++ b/g2o/examples/interactive_slam/g2o_incremental/linear_solver_cholmod_online.h @@ -25,6 +25,7 @@ #include "g2o/core/batch_stats.h" #include "g2o/core/linear_solver.h" #include "g2o/solvers/cholmod/cholmod_ext.h" +#include "g2o/stuff/logger.h" #include "g2o/stuff/timeutil.h" #include "g2o_incremental_api.h" @@ -138,7 +139,7 @@ class LinearSolverCholmodOnline : public LinearSolver, int choleskyUpdate(cholmod_sparse* update) { int result = cholmod_updown(1, update, _cholmodFactor, &_cholmodCommon); - // std::cerr << __PRETTY_FUNCTION__ << " " << result << std::endl; + G2O_TRACE("result {}", result); if (_cholmodCommon.status == CHOLMOD_NOT_POSDEF) { std::cerr << "Cholesky failure, writing debug.txt (Hessian loadable by Octave)" @@ -235,8 +236,7 @@ class LinearSolverCholmodOnline : public LinearSolver, size_t n = A.cols() + additionalSpace; if (_cholmodSparse->columnsAllocated < n) { - // std::cerr << __PRETTY_FUNCTION__ << ": reallocating columns" << - // std::endl; + G2O_DEBUG("reallocating columns"); _cholmodSparse->columnsAllocated = _cholmodSparse->columnsAllocated == 0 ? n @@ -247,8 +247,7 @@ class LinearSolverCholmodOnline : public LinearSolver, if (!onlyValues) { size_t nzmax = A.nonZeros() + additionalSpace; if (_cholmodSparse->nzmax < nzmax) { - // std::cerr << __PRETTY_FUNCTION__ << ": reallocating row + values" << - // std::endl; + G2O_DEBUG("reallocating row + values"); _cholmodSparse->nzmax = _cholmodSparse->nzmax == 0 ? nzmax diff --git a/g2o/examples/interactive_slam/g2o_interactive/g2o_online.cpp b/g2o/examples/interactive_slam/g2o_interactive/g2o_online.cpp index 71b4e233a..452b569f1 100644 --- a/g2o/examples/interactive_slam/g2o_interactive/g2o_online.cpp +++ b/g2o/examples/interactive_slam/g2o_interactive/g2o_online.cpp @@ -26,12 +26,9 @@ #include #include -#include -#include #include "g2o/stuff/command_args.h" -#include "g2o/stuff/macros.h" -#include "g2o/stuff/timeutil.h" +#include "g2o/stuff/logger.h" #include "g2o_slam_interface.h" #include "graph_optimizer_sparse_online.h" #include "slam_parser/interface/parser_interface.h" @@ -46,7 +43,7 @@ void sigquit_handler(int sig) { hasToStop = 1; static int cnt = 0; if (cnt++ == 2) { - cerr << __PRETTY_FUNCTION__ << " forcing exit" << endl; + G2O_WARN("forcing exit"); exit(1); } } diff --git a/g2o/examples/interactive_slam/g2o_interactive/g2o_slam_interface.cpp b/g2o/examples/interactive_slam/g2o_interactive/g2o_slam_interface.cpp index ecb9b2dd9..4f9763bd8 100644 --- a/g2o/examples/interactive_slam/g2o_interactive/g2o_slam_interface.cpp +++ b/g2o/examples/interactive_slam/g2o_interactive/g2o_slam_interface.cpp @@ -30,6 +30,7 @@ #include #include "fast_output.h" +#include "g2o/stuff/logger.h" #include "g2o/types/slam3d/se3quat.h" #include "graph_optimizer_sparse_online.h" #include "types_slam2d_online.h" @@ -317,8 +318,7 @@ bool G2oSlamInterface::addEdge(const std::string& tag, int id, int dimension, } } else { - cerr << __PRETTY_FUNCTION__ << " not implemented for this dimension" - << endl; + G2O_ERROR("not implemented for this dimension {}", dimension); return false; } diff --git a/g2o/examples/interactive_slam/g2o_interactive/generate_commands.cpp b/g2o/examples/interactive_slam/g2o_interactive/generate_commands.cpp index f5aaf82b4..0bd7e9ece 100644 --- a/g2o/examples/interactive_slam/g2o_interactive/generate_commands.cpp +++ b/g2o/examples/interactive_slam/g2o_interactive/generate_commands.cpp @@ -28,19 +28,13 @@ #include #include #include -#include #include -#include #include #include "g2o/core/factory.h" #include "g2o/core/sparse_optimizer.h" -#include "g2o/stuff/color_macros.h" #include "g2o/stuff/command_args.h" -#include "g2o/stuff/filesys_tools.h" -#include "g2o/stuff/macros.h" -#include "g2o/stuff/string_tools.h" -#include "g2o/stuff/timeutil.h" +#include "g2o/stuff/logger.h" static bool hasToStop = false; @@ -79,7 +73,7 @@ void sigquit_handler(int sig) { hasToStop = 1; static int cnt = 0; if (cnt++ == 2) { - cerr << __PRETTY_FUNCTION__ << " forcing exit" << endl; + G2O_WARN("forcing exit"); exit(1); } } diff --git a/g2o/examples/interactive_slam/g2o_interactive/graph_optimizer_sparse_online.cpp b/g2o/examples/interactive_slam/g2o_interactive/graph_optimizer_sparse_online.cpp index 46a9c082d..e960ba230 100644 --- a/g2o/examples/interactive_slam/g2o_interactive/graph_optimizer_sparse_online.cpp +++ b/g2o/examples/interactive_slam/g2o_interactive/graph_optimizer_sparse_online.cpp @@ -26,14 +26,12 @@ #include "graph_optimizer_sparse_online.h" -#include -#include #include #include "g2o/core/block_solver.h" #include "g2o/core/optimization_algorithm_factory.h" #include "g2o/core/optimization_algorithm_gauss_newton.h" -#include "g2o/solvers/cholmod/linear_solver_cholmod.h" +#include "g2o/solvers/cholmod/linear_solver_cholmod.h" // IWYU pragma: keep #include "g2o/solvers/pcg/linear_solver_pcg.h" #include "g2o/stuff/macros.h" #include "types_slam2d_online.h" @@ -92,8 +90,7 @@ int SparseOptimizerOnline::optimize(int iterations, bool online) { if (!online) { ok = _underlyingSolver->buildStructure(); if (!ok) { - cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" - << endl; + G2O_ERROR("Failure while building CCS structure"); return 0; } } diff --git a/g2o/solvers/csparse/csparse_extension.cpp b/g2o/solvers/csparse/csparse_extension.cpp index 9530da7ba..fe7061da3 100644 --- a/g2o/solvers/csparse/csparse_extension.cpp +++ b/g2o/solvers/csparse/csparse_extension.cpp @@ -34,14 +34,14 @@ int cs_cholsolsymb(const cs* A, double* b, const css* S, double* x, int* work) { csn* N; int n, ok; if (!CS_CSC(A) || !b || !S || !x) { - G2O_DEBUG("{}: No valid input!", __PRETTY_FUNCTION__); + G2O_DEBUG("No valid input!"); assert(0); // get a backtrace in debug mode return (0); /* check inputs */ } n = A->n; N = cs_chol_workspace(A, S, work, x); /* numeric Cholesky factorization */ if (!N) { - G2O_DEBUG("{}: cholesky failed!", __PRETTY_FUNCTION__); + G2O_DEBUG("cholesky failed!"); } ok = (N != NULL); if (ok) { diff --git a/g2o/solvers/slam2d_linear/solver_slam2d_linear.cpp b/g2o/solvers/slam2d_linear/solver_slam2d_linear.cpp index a850f03c0..bd212dda7 100644 --- a/g2o/solvers/slam2d_linear/solver_slam2d_linear.cpp +++ b/g2o/solvers/slam2d_linear/solver_slam2d_linear.cpp @@ -208,7 +208,7 @@ bool SolverSLAM2DLinear::solveOrientation() { linearSystemSolver.init(); bool ok = linearSystemSolver.solve(H, x.data(), b.data()); if (!ok) { - G2O_ERROR("{} Failure while solving linear system", __PRETTY_FUNCTION__); + G2O_ERROR("Failure while solving linear system"); return false; } diff --git a/g2o/stuff/macros.h b/g2o/stuff/macros.h index 0e876110b..7970f0411 100644 --- a/g2o/stuff/macros.h +++ b/g2o/stuff/macros.h @@ -47,7 +47,6 @@ // MSVC on Windows #elif defined _MSC_VER -#define __PRETTY_FUNCTION__ __FUNCTION__ /** Modified by Mark Pupilli from: @@ -74,9 +73,6 @@ for static C++ objects. For GCC, uses a constructor attribute." // unknown compiler #else -#ifndef __PRETTY_FUNCTION__ -#define __PRETTY_FUNCTION__ "" -#endif #define G2O_ATTRIBUTE_CONSTRUCTOR(func) func #define G2O_ATTRIBUTE_UNUSED #define G2O_ATTRIBUTE_WARNING(func) func diff --git a/g2o/stuff/property.cpp b/g2o/stuff/property.cpp index bfb77feab..e5fba705f 100644 --- a/g2o/stuff/property.cpp +++ b/g2o/stuff/property.cpp @@ -86,8 +86,7 @@ bool PropertyMap::updateMapFromString(const std::string& values) { for (size_t i = 0; i < valuesMap.size(); ++i) { vector m = strSplit(valuesMap[i], "="); if (m.size() != 2) { - G2O_DEBUG("{}: unable to extract name=value pair from {}", - __PRETTY_FUNCTION__, valuesMap[i]); + G2O_DEBUG("unable to extract name=value pair from {}", valuesMap[i]); continue; } string name = trim(m[0]); diff --git a/g2o/stuff/timeutil.h b/g2o/stuff/timeutil.h index 1dac3e704..c8b9c62a3 100644 --- a/g2o/stuff/timeutil.h +++ b/g2o/stuff/timeutil.h @@ -30,7 +30,6 @@ #include #include -#include "g2o/stuff/misc.h" #include "g2o_stuff_api.h" /** @addtogroup utils **/ @@ -109,7 +108,7 @@ class G2O_STUFF_API ScopeTime { } // namespace g2o #ifndef MEASURE_FUNCTION_TIME -#define MEASURE_FUNCTION_TIME g2o::ScopeTime scopeTime(__PRETTY_FUNCTION__) +#define MEASURE_FUNCTION_TIME g2o::ScopeTime scopeTime(__FUNCTION__) #endif // @}