Skip to content

Commit

Permalink
Fixed g2o version not correctly used, D400: set default to IR+Depth
Browse files Browse the repository at this point in the history
  • Loading branch information
matlabbe committed Mar 14, 2023
1 parent 92b9cc8 commit 6fe5e63
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 4 deletions.
6 changes: 3 additions & 3 deletions corelib/src/optimizer/OptimizerG2O.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ OptimizerG2O::OptimizerG2O(const ParametersMap & parameters) :
// Issue on android, have to explicitly register this type when using fixed root prior below
if(!g2o::Factory::instance()->knowsTag("CACHE_SE3_OFFSET"))
{
#if defined(RTABMAP_G2O_CPP11) and RTABMAP_G2O_CPP11 == 1
#if defined(RTABMAP_G2O_CPP11) && RTABMAP_G2O_CPP11 == 1
g2o::Factory::instance()->registerType("CACHE_SE3_OFFSET", g2o::make_unique<g2o::HyperGraphElementCreator<g2o::CacheSE3Offset> >());
#else
g2o::Factory::instance()->registerType("CACHE_SE3_OFFSET", new g2o::HyperGraphElementCreator<g2o::CacheSE3Offset>);
Expand Down Expand Up @@ -1414,7 +1414,7 @@ std::map<int, Transform> OptimizerG2O::optimizeBA(
{
g2o::SparseOptimizer optimizer;
//optimizer.setVerbose(ULogger::level()==ULogger::kDebug);
#if defined(RTABMAP_G2O_CPP11) and not defined(RTABMAP_ORB_SLAM)
#if defined(RTABMAP_G2O_CPP11) && !defined(RTABMAP_ORB_SLAM)
std::unique_ptr<g2o::BlockSolver_6_3::LinearSolverType> linearSolver;
#else
g2o::BlockSolver_6_3::LinearSolverType * linearSolver = 0;
Expand Down Expand Up @@ -1478,7 +1478,7 @@ std::map<int, Transform> OptimizerG2O::optimizeBA(
else
#endif
{
#if defined(RTABMAP_G2O_CPP11) and not defined(RTABMAP_ORB_SLAM)
#if defined(RTABMAP_G2O_CPP11) && !defined(RTABMAP_ORB_SLAM)
optimizer.setAlgorithm(new g2o::OptimizationAlgorithmLevenberg(
g2o::make_unique<g2o::BlockSolver_6_3>(std::move(linearSolver))));
#else
Expand Down
6 changes: 5 additions & 1 deletion guilib/src/PreferencesDialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3921,12 +3921,16 @@ void PreferencesDialog::selectSourceDriver(Src src, int variant)
_ui->spinBox_rs2_width->setValue(1280);
_ui->spinBox_rs2_height->setValue(720);
_ui->spinBox_rs2_rate->setValue(30);
_ui->checkbox_rs2_irMode->setChecked(false);
_ui->checkbox_rs2_emitter->setChecked(true);
}
else
else // D400
{
_ui->spinBox_rs2_width->setValue(848);
_ui->spinBox_rs2_height->setValue(480);
_ui->spinBox_rs2_rate->setValue(60);
_ui->checkbox_rs2_irMode->setChecked(true);
_ui->checkbox_rs2_emitter->setChecked(false);
}
}
}
Expand Down

0 comments on commit 6fe5e63

Please sign in to comment.