Skip to content

Commit 948e15c

Browse files
authored
Supplement and Adjust OpenVINS Parameters (#1145)
* set the PrintLevel of OpenVINS to be equivalent to that of ULogger * use global FAST settings * add online calibration params * add dynamic initialization params * add necessary feature initializer options * fix segfault of OdomImageDecimation * add mask settings * use depth as mask in OpenVINS * set twist covariance * restore default values of VisMinDepth and VisMaxDepth
1 parent f06cc0b commit 948e15c

File tree

7 files changed

+741
-121
lines changed

7 files changed

+741
-121
lines changed

corelib/include/rtabmap/core/Parameters.h

Lines changed: 62 additions & 42 deletions
Large diffs are not rendered by default.

corelib/include/rtabmap/core/odometry/OdometryOpenVINS.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@ class RTABMAP_CORE_EXPORT OdometryOpenVINS : public Odometry
5757
bool initGravity_;
5858
Transform previousPoseInv_;
5959
Transform imuLocalTransformInv_;
60+
Eigen::Matrix<double, 6, 6> Phi_;
6061
#endif
6162
};
6263

corelib/src/Odometry.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -675,12 +675,12 @@ Transform Odometry::process(SensorData & data, const Transform & guessIn, Odomet
675675
UASSERT(info->newCorners.size() == info->refCorners.size() || info->refCorners.empty());
676676
for(unsigned int i=0; i<info->newCorners.size(); ++i)
677677
{
678-
info->refCorners[i].x *= _imageDecimation;
679-
info->refCorners[i].y *= _imageDecimation;
678+
info->newCorners[i].x *= _imageDecimation;
679+
info->newCorners[i].y *= _imageDecimation;
680680
if(!info->refCorners.empty())
681681
{
682-
info->newCorners[i].x *= _imageDecimation;
683-
info->newCorners[i].y *= _imageDecimation;
682+
info->refCorners[i].x *= _imageDecimation;
683+
info->refCorners[i].y *= _imageDecimation;
684684
}
685685
}
686686
for(std::multimap<int, cv::KeyPoint>::iterator iter=info->words.begin(); iter!=info->words.end(); ++iter)

corelib/src/odometry/OdometryOpenVINS.cpp

Lines changed: 90 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -28,12 +28,15 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
2828
#include "rtabmap/core/odometry/OdometryOpenVINS.h"
2929
#include "rtabmap/core/OdometryInfo.h"
3030
#include "rtabmap/core/util3d_transforms.h"
31+
#include "rtabmap/utilite/UFile.h"
3132
#include "rtabmap/utilite/ULogger.h"
3233
#include "rtabmap/utilite/UTimer.h"
34+
#include <opencv2/core/eigen.hpp>
3335
#include <opencv2/imgproc/types_c.h>
3436

3537
#ifdef RTABMAP_OPENVINS
3638
#include "core/VioManager.h"
39+
#include "state/Propagator.h"
3740
#include "state/State.h"
3841
#include "state/StateHelper.h"
3942
#endif
@@ -49,20 +52,35 @@ OdometryOpenVINS::OdometryOpenVINS(const ParametersMap & parameters) :
4952
#endif
5053
{
5154
#ifdef RTABMAP_OPENVINS
52-
ov_core::Printer::setPrintLevel("WARNING");
55+
ov_core::Printer::setPrintLevel(ov_core::Printer::PrintLevel(ULogger::level()+1));
5356
int enum_index;
57+
std::string left_mask_path, right_mask_path;
5458
params_ = std::make_unique<ov_msckf::VioManagerOptions>();
5559
Parameters::parse(parameters, Parameters::kOdomOpenVINSUseStereo(), params_->use_stereo);
5660
Parameters::parse(parameters, Parameters::kOdomOpenVINSUseKLT(), params_->use_klt);
5761
Parameters::parse(parameters, Parameters::kOdomOpenVINSNumPts(), params_->num_pts);
58-
Parameters::parse(parameters, Parameters::kOdomOpenVINSFastThreshold(), params_->fast_threshold);
59-
Parameters::parse(parameters, Parameters::kOdomOpenVINSGridX(), params_->grid_x);
60-
Parameters::parse(parameters, Parameters::kOdomOpenVINSGridY(), params_->grid_y);
62+
Parameters::parse(parameters, Parameters::kFASTThreshold(), params_->fast_threshold);
63+
Parameters::parse(parameters, Parameters::kVisGridCols(), params_->grid_x);
64+
Parameters::parse(parameters, Parameters::kVisGridRows(), params_->grid_y);
6165
Parameters::parse(parameters, Parameters::kOdomOpenVINSMinPxDist(), params_->min_px_dist);
62-
Parameters::parse(parameters, Parameters::kOdomOpenVINSKNNRatio(), params_->knn_ratio);
66+
Parameters::parse(parameters, Parameters::kVisCorNNDR(), params_->knn_ratio);
67+
Parameters::parse(parameters, Parameters::kOdomOpenVINSFiTriangulate1d(), params_->featinit_options.triangulate_1d);
68+
Parameters::parse(parameters, Parameters::kOdomOpenVINSFiRefineFeatures(), params_->featinit_options.refine_features);
69+
Parameters::parse(parameters, Parameters::kOdomOpenVINSFiMaxRuns(), params_->featinit_options.max_runs);
70+
Parameters::parse(parameters, Parameters::kVisMinDepth(), params_->featinit_options.min_dist);
71+
Parameters::parse(parameters, Parameters::kVisMaxDepth(), params_->featinit_options.max_dist);
72+
if(params_->featinit_options.max_dist == 0)
73+
params_->featinit_options.max_dist = std::numeric_limits<double>::infinity();
74+
Parameters::parse(parameters, Parameters::kOdomOpenVINSFiMaxBaseline(), params_->featinit_options.max_baseline);
75+
Parameters::parse(parameters, Parameters::kOdomOpenVINSFiMaxCondNumber(), params_->featinit_options.max_cond_number);
6376
Parameters::parse(parameters, Parameters::kOdomOpenVINSUseFEJ(), params_->state_options.do_fej);
6477
Parameters::parse(parameters, Parameters::kOdomOpenVINSIntegration(), enum_index);
6578
params_->state_options.integration_method = ov_msckf::StateOptions::IntegrationMethod(enum_index);
79+
Parameters::parse(parameters, Parameters::kOdomOpenVINSCalibCamExtrinsics(), params_->state_options.do_calib_camera_pose);
80+
Parameters::parse(parameters, Parameters::kOdomOpenVINSCalibCamIntrinsics(), params_->state_options.do_calib_camera_intrinsics);
81+
Parameters::parse(parameters, Parameters::kOdomOpenVINSCalibCamTimeoffset(), params_->state_options.do_calib_camera_timeoffset);
82+
Parameters::parse(parameters, Parameters::kOdomOpenVINSCalibIMUIntrinsics(), params_->state_options.do_calib_imu_intrinsics);
83+
Parameters::parse(parameters, Parameters::kOdomOpenVINSCalibIMUGSensitivity(), params_->state_options.do_calib_imu_g_sensitivity);
6684
Parameters::parse(parameters, Parameters::kOdomOpenVINSMaxClones(), params_->state_options.max_clone_size);
6785
Parameters::parse(parameters, Parameters::kOdomOpenVINSMaxSLAM(), params_->state_options.max_slam_features);
6886
Parameters::parse(parameters, Parameters::kOdomOpenVINSMaxSLAMInUpdate(), params_->state_options.max_slam_in_update);
@@ -73,10 +91,39 @@ OdometryOpenVINS::OdometryOpenVINS(const ParametersMap & parameters) :
7391
params_->state_options.feat_rep_slam = ov_type::LandmarkRepresentation::Representation(enum_index);
7492
Parameters::parse(parameters, Parameters::kOdomOpenVINSDtSLAMDelay(), params_->dt_slam_delay);
7593
Parameters::parse(parameters, Parameters::kOdomOpenVINSGravityMag(), params_->gravity_mag);
94+
Parameters::parse(parameters, Parameters::kVisDepthAsMask(), params_->use_mask);
95+
Parameters::parse(parameters, Parameters::kOdomOpenVINSLeftMaskPath(), left_mask_path);
96+
if(!left_mask_path.empty())
97+
{
98+
if(!UFile::exists(left_mask_path))
99+
UWARN("OpenVINS: invalid left mask path: %s", left_mask_path.c_str());
100+
else
101+
params_->masks.emplace(0, cv::imread(left_mask_path, cv::IMREAD_GRAYSCALE));
102+
}
103+
Parameters::parse(parameters, Parameters::kOdomOpenVINSRightMaskPath(), right_mask_path);
104+
if(!right_mask_path.empty())
105+
{
106+
if(!UFile::exists(right_mask_path))
107+
UWARN("OpenVINS: invalid right mask path: %s", right_mask_path.c_str());
108+
else
109+
params_->masks.emplace(1, cv::imread(right_mask_path, cv::IMREAD_GRAYSCALE));
110+
}
76111
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitWindowTime(), params_->init_options.init_window_time);
77112
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitIMUThresh(), params_->init_options.init_imu_thresh);
78113
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitMaxDisparity(), params_->init_options.init_max_disparity);
79114
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitMaxFeatures(), params_->init_options.init_max_features);
115+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynUse(), params_->init_options.init_dyn_use);
116+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynMLEOptCalib(), params_->init_options.init_dyn_mle_opt_calib);
117+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynMLEMaxIter(), params_->init_options.init_dyn_mle_max_iter);
118+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynMLEMaxTime(), params_->init_options.init_dyn_mle_max_time);
119+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynMLEMaxThreads(), params_->init_options.init_dyn_mle_max_threads);
120+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynNumPose(), params_->init_options.init_dyn_num_pose);
121+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynMinDeg(), params_->init_options.init_dyn_min_deg);
122+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynInflationOri(), params_->init_options.init_dyn_inflation_orientation);
123+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynInflationVel(), params_->init_options.init_dyn_inflation_velocity);
124+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynInflationBg(), params_->init_options.init_dyn_inflation_bias_gyro);
125+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynInflationBa(), params_->init_options.init_dyn_inflation_bias_accel);
126+
Parameters::parse(parameters, Parameters::kOdomOpenVINSInitDynMinRecCond(), params_->init_options.init_dyn_min_rec_cond);
80127
Parameters::parse(parameters, Parameters::kOdomOpenVINSTryZUPT(), params_->try_zupt);
81128
Parameters::parse(parameters, Parameters::kOdomOpenVINSZUPTChi2Multiplier(), params_->zupt_options.chi2_multipler);
82129
Parameters::parse(parameters, Parameters::kOdomOpenVINSZUPTMaxVelodicy(), params_->zupt_max_velocity);
@@ -134,7 +181,12 @@ Transform OdometryOpenVINS::computeTransform(
134181
if(!vioManager_)
135182
{
136183
if(!data.imu().empty())
184+
{
137185
imuLocalTransformInv_ = data.imu().localTransform().inverse();
186+
Phi_.setZero();
187+
Phi_.block(0,0,3,3) = data.imu().localTransform().toEigen4d().block(0,0,3,3);
188+
Phi_.block(3,3,3,3) = data.imu().localTransform().toEigen4d().block(0,0,3,3);
189+
}
138190

139191
if(!data.imageRaw().empty() && !imuLocalTransformInv_.isNull())
140192
{
@@ -280,6 +332,12 @@ Transform OdometryOpenVINS::computeTransform(
280332

281333
if(!data.imageRaw().empty())
282334
{
335+
bool covFilled = false;
336+
Eigen::Matrix<double, 13, 1> state_plus = Eigen::Matrix<double, 13, 1>::Zero();
337+
Eigen::Matrix<double, 12, 12> cov_plus = Eigen::Matrix<double, 12, 12>::Zero();
338+
if(vioManager_->initialized())
339+
covFilled = vioManager_->get_propagator()->fast_state_propagate(vioManager_->get_state(), data.stamp(), state_plus, cov_plus);
340+
283341
cv::Mat image;
284342
if(data.imageRaw().type() == CV_8UC3)
285343
cv::cvtColor(data.imageRaw(), image, CV_BGR2GRAY);
@@ -291,7 +349,25 @@ Transform OdometryOpenVINS::computeTransform(
291349
message.timestamp = data.stamp();
292350
message.sensor_ids.emplace_back(0);
293351
message.images.emplace_back(image);
294-
message.masks.emplace_back(cv::Mat::zeros(image.size(), CV_8UC1));
352+
if(params_->masks.find(0) != params_->masks.end())
353+
{
354+
message.masks.emplace_back(params_->masks[0]);
355+
}
356+
else if(!data.depthRaw().empty() && params_->use_mask)
357+
{
358+
cv::Mat mask;
359+
if(data.depthRaw().type() == CV_32FC1)
360+
cv::inRange(data.depthRaw(), params_->featinit_options.min_dist,
361+
std::isinf(params_->featinit_options.max_dist)?std::numeric_limits<float>::max():params_->featinit_options.max_dist, mask);
362+
else if(data.depthRaw().type() == CV_16UC1)
363+
cv::inRange(data.depthRaw(), params_->featinit_options.min_dist*1000,
364+
std::isinf(params_->featinit_options.max_dist)?std::numeric_limits<uint16_t>::max():params_->featinit_options.max_dist*1000, mask);
365+
message.masks.emplace_back(255-mask);
366+
}
367+
else
368+
{
369+
message.masks.emplace_back(cv::Mat::zeros(image.size(), CV_8UC1));
370+
}
295371
if(!data.rightRaw().empty())
296372
{
297373
if(data.rightRaw().type() == CV_8UC3)
@@ -302,7 +378,10 @@ Transform OdometryOpenVINS::computeTransform(
302378
UFATAL("Not supported color type!");
303379
message.sensor_ids.emplace_back(1);
304380
message.images.emplace_back(image);
305-
message.masks.emplace_back(cv::Mat::zeros(image.size(), CV_8UC1));
381+
if(params_->masks.find(1) != params_->masks.end())
382+
message.masks.emplace_back(params_->masks[1]);
383+
else
384+
message.masks.emplace_back(cv::Mat::zeros(image.size(), CV_8UC1));
306385
}
307386
vioManager_->feed_measurement_camera(message);
308387

@@ -342,17 +421,11 @@ Transform OdometryOpenVINS::computeTransform(
342421
info->type = this->getType();
343422
info->localMapSize = feat_posinG.size();
344423
info->features = features_SLAM.size() + good_features_MSCKF.size();
345-
info->reg.covariance = cv::Mat(6,6,CV_64FC1);
346-
std::vector<std::shared_ptr<ov_type::Type>> statevars;
347-
statevars.emplace_back(state->_imu->pose()->p());
348-
statevars.emplace_back(state->_imu->pose()->q());
349-
Eigen::Matrix<double,6,6> covariance_posori = ov_msckf::StateHelper::get_marginal_covariance(state, statevars);
350-
for (int r = 0; r < 6; r++)
424+
info->reg.covariance = cv::Mat::eye(6, 6, CV_64FC1);
425+
if(covFilled)
351426
{
352-
for (int c = 0; c < 6; c++)
353-
{
354-
((double *)info->reg.covariance.data)[6*r+c] = covariance_posori(r,c);
355-
}
427+
Eigen::Matrix<double, 6, 6> covariance = Phi_ * cov_plus.block(6,6,6,6) * Phi_.transpose();
428+
cv::eigen2cv(covariance, info->reg.covariance);
356429
}
357430

358431
if(this->isInfoDataFilled())

guilib/include/rtabmap/gui/PreferencesDialog.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -349,6 +349,8 @@ private Q_SLOTS:
349349
void changeOdometryORBSLAMVocabulary();
350350
void changeOdometryOKVISConfigPath();
351351
void changeOdometryVINSConfigPath();
352+
void changeOdometryOpenVINSLeftMask();
353+
void changeOdometryOpenVINSRightMask();
352354
void changeIcpPMConfigPath();
353355
void changeSuperPointModelPath();
354356
void changePyMatcherPath();

guilib/src/PreferencesDialog.cpp

Lines changed: 60 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1437,14 +1437,20 @@ PreferencesDialog::PreferencesDialog(QWidget * parent) :
14371437
_ui->checkBox_OdomOpenVINSUseStereo->setObjectName(Parameters::kOdomOpenVINSUseStereo().c_str());
14381438
_ui->checkBox_OdomOpenVINSUseKLT->setObjectName(Parameters::kOdomOpenVINSUseKLT().c_str());
14391439
_ui->spinBox_OdomOpenVINSNumPts->setObjectName(Parameters::kOdomOpenVINSNumPts().c_str());
1440-
_ui->spinBox_OdomOpenVINSFastThreshold->setObjectName(Parameters::kOdomOpenVINSFastThreshold().c_str());
1441-
_ui->spinBox_OdomOpenVINSGridX->setObjectName(Parameters::kOdomOpenVINSGridX().c_str());
1442-
_ui->spinBox_OdomOpenVINSGridY->setObjectName(Parameters::kOdomOpenVINSGridY().c_str());
14431440
_ui->spinBox_OdomOpenVINSMinPxDist->setObjectName(Parameters::kOdomOpenVINSMinPxDist().c_str());
1444-
_ui->doubleSpinBox_OdomOpenVINSKNNRatio->setObjectName(Parameters::kOdomOpenVINSKNNRatio().c_str());
1441+
_ui->checkBox_OdomOpenVINSFiTriangulate1d->setObjectName(Parameters::kOdomOpenVINSFiTriangulate1d().c_str());
1442+
_ui->checkBox_OdomOpenVINSFiRefineFeatures->setObjectName(Parameters::kOdomOpenVINSFiRefineFeatures().c_str());
1443+
_ui->spinBox_OdomOpenVINSFiMaxRuns->setObjectName(Parameters::kOdomOpenVINSFiMaxRuns().c_str());
1444+
_ui->doubleSpinBox_OdomOpenVINSFiMaxBaseline->setObjectName(Parameters::kOdomOpenVINSFiMaxBaseline().c_str());
1445+
_ui->doubleSpinBox_OdomOpenVINSFiMaxCondNumber->setObjectName(Parameters::kOdomOpenVINSFiMaxCondNumber().c_str());
14451446

14461447
_ui->checkBox_OdomOpenVINSUseFEJ->setObjectName(Parameters::kOdomOpenVINSUseFEJ().c_str());
14471448
_ui->comboBox_OdomOpenVINSIntegration->setObjectName(Parameters::kOdomOpenVINSIntegration().c_str());
1449+
_ui->checkBox_OdomOpenVINSCalibCamExtrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamExtrinsics().c_str());
1450+
_ui->checkBox_OdomOpenVINSCalibCamIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamIntrinsics().c_str());
1451+
_ui->checkBox_OdomOpenVINSCalibCamTimeoffset->setObjectName(Parameters::kOdomOpenVINSCalibCamTimeoffset().c_str());
1452+
_ui->checkBox_OdomOpenVINSCalibIMUIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibIMUIntrinsics().c_str());
1453+
_ui->checkBox_OdomOpenVINSCalibIMUGSensitivity->setObjectName(Parameters::kOdomOpenVINSCalibIMUGSensitivity().c_str());
14481454
_ui->spinBox_OdomOpenVINSMaxClones->setObjectName(Parameters::kOdomOpenVINSMaxClones().c_str());
14491455
_ui->spinBox_OdomOpenVINSMaxSLAM->setObjectName(Parameters::kOdomOpenVINSMaxSLAM().c_str());
14501456
_ui->spinBox_OdomOpenVINSMaxSLAMInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxSLAMInUpdate().c_str());
@@ -1453,11 +1459,27 @@ PreferencesDialog::PreferencesDialog(QWidget * parent) :
14531459
_ui->comboBox_OdomOpenVINSFeatRepSLAM->setObjectName(Parameters::kOdomOpenVINSFeatRepSLAM().c_str());
14541460
_ui->doubleSpinBox_OdomOpenVINSDtSLAMDelay->setObjectName(Parameters::kOdomOpenVINSDtSLAMDelay().c_str());
14551461
_ui->doubleSpinBox_OdomOpenVINSGravityMag->setObjectName(Parameters::kOdomOpenVINSGravityMag().c_str());
1462+
_ui->lineEdit_OdomOpenVINSLeftMaskPath->setObjectName(Parameters::kOdomOpenVINSLeftMaskPath().c_str());
1463+
connect(_ui->toolButton_OdomOpenVINSLeftMaskPath, SIGNAL(clicked()), this, SLOT(changeOdometryOpenVINSLeftMask()));
1464+
_ui->lineEdit_OdomOpenVINSRightMaskPath->setObjectName(Parameters::kOdomOpenVINSRightMaskPath().c_str());
1465+
connect(_ui->toolButton_OdomOpenVINSRightMaskPath, SIGNAL(clicked()), this, SLOT(changeOdometryOpenVINSRightMask()));
14561466

14571467
_ui->doubleSpinBox_OdomOpenVINSInitWindowTime->setObjectName(Parameters::kOdomOpenVINSInitWindowTime().c_str());
14581468
_ui->doubleSpinBox_OdomOpenVINSInitIMUThresh->setObjectName(Parameters::kOdomOpenVINSInitIMUThresh().c_str());
14591469
_ui->doubleSpinBox_OdomOpenVINSInitMaxDisparity->setObjectName(Parameters::kOdomOpenVINSInitMaxDisparity().c_str());
14601470
_ui->spinBox_OdomOpenVINSInitMaxFeatures->setObjectName(Parameters::kOdomOpenVINSInitMaxFeatures().c_str());
1471+
_ui->checkBox_OdomOpenVINSInitDynUse->setObjectName(Parameters::kOdomOpenVINSInitDynUse().c_str());
1472+
_ui->checkBox_OdomOpenVINSInitDynMLEOptCalib->setObjectName(Parameters::kOdomOpenVINSInitDynMLEOptCalib().c_str());
1473+
_ui->spinBox_OdomOpenVINSInitDynMLEMaxIter->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxIter().c_str());
1474+
_ui->doubleSpinBox_OdomOpenVINSInitDynMLEMaxTime->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxTime().c_str());
1475+
_ui->spinBox_OdomOpenVINSInitDynMLEMaxThreads->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxThreads().c_str());
1476+
_ui->spinBox_OdomOpenVINSInitDynNumPose->setObjectName(Parameters::kOdomOpenVINSInitDynNumPose().c_str());
1477+
_ui->doubleSpinBox_OdomOpenVINSInitDynMinDeg->setObjectName(Parameters::kOdomOpenVINSInitDynMinDeg().c_str());
1478+
_ui->doubleSpinBox_OdomOpenVINSInitDynInflationOri->setObjectName(Parameters::kOdomOpenVINSInitDynInflationOri().c_str());
1479+
_ui->doubleSpinBox_OdomOpenVINSInitDynInflationVel->setObjectName(Parameters::kOdomOpenVINSInitDynInflationVel().c_str());
1480+
_ui->doubleSpinBox_OdomOpenVINSInitDynInflationBg->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBg().c_str());
1481+
_ui->doubleSpinBox_OdomOpenVINSInitDynInflationBa->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBa().c_str());
1482+
_ui->doubleSpinBox_OdomOpenVINSInitDynMinRecCond->setObjectName(Parameters::kOdomOpenVINSInitDynMinRecCond().c_str());
14611483

14621484
_ui->checkBox_OdomOpenVINSTryZUPT->setObjectName(Parameters::kOdomOpenVINSTryZUPT().c_str());
14631485
_ui->doubleSpinBox_OdomOpenVINSZUPTChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSZUPTChi2Multiplier().c_str());
@@ -5194,6 +5216,40 @@ void PreferencesDialog::changeOdometryVINSConfigPath()
51945216
}
51955217
}
51965218

5219+
void PreferencesDialog::changeOdometryOpenVINSLeftMask()
5220+
{
5221+
QString path;
5222+
if(_ui->lineEdit_OdomOpenVINSLeftMaskPath->text().isEmpty())
5223+
{
5224+
path = QFileDialog::getOpenFileName(this, tr("Select Left Mask"), this->getWorkingDirectory(), tr("Image mask (*.jpg *.png)"));
5225+
}
5226+
else
5227+
{
5228+
path = QFileDialog::getOpenFileName(this, tr("Select Left Mask"), _ui->lineEdit_OdomOpenVINSLeftMaskPath->text(), tr("Image mask (*.jpg *.png)"));
5229+
}
5230+
if(!path.isEmpty())
5231+
{
5232+
_ui->lineEdit_OdomOpenVINSLeftMaskPath->setText(path);
5233+
}
5234+
}
5235+
5236+
void PreferencesDialog::changeOdometryOpenVINSRightMask()
5237+
{
5238+
QString path;
5239+
if(_ui->lineEdit_OdomOpenVINSRightMaskPath->text().isEmpty())
5240+
{
5241+
path = QFileDialog::getOpenFileName(this, tr("Select Right Mask"), this->getWorkingDirectory(), tr("Image mask (*.jpg *.png)"));
5242+
}
5243+
else
5244+
{
5245+
path = QFileDialog::getOpenFileName(this, tr("Select Right Mask"), _ui->lineEdit_OdomOpenVINSRightMaskPath->text(), tr("Image mask (*.jpg *.png)"));
5246+
}
5247+
if(!path.isEmpty())
5248+
{
5249+
_ui->lineEdit_OdomOpenVINSRightMaskPath->setText(path);
5250+
}
5251+
}
5252+
51975253
void PreferencesDialog::changeIcpPMConfigPath()
51985254
{
51995255
QString path;

0 commit comments

Comments
 (0)