diff --git a/corelib/include/rtabmap/core/camera/CameraDepthAI.h b/corelib/include/rtabmap/core/camera/CameraDepthAI.h index d556e7bcb1..ba88a00ec8 100644 --- a/corelib/include/rtabmap/core/camera/CameraDepthAI.h +++ b/corelib/include/rtabmap/core/camera/CameraDepthAI.h @@ -55,13 +55,11 @@ class RTABMAP_CORE_EXPORT CameraDepthAI : const Transform & localTransform = Transform::getIdentity()); virtual ~CameraDepthAI(); - void setOutputDepth(bool enabled, int confidence = 200); - void setUseSpecTranslation(bool useSpecTranslation); - void setAlphaScaling(float alphaScaling = 0.0f); - void setIMUPublished(bool published); - void publishInterIMU(bool enabled); - void setLaserDotBrightness(float dotProjectormA = 0.0f); - void setFloodLightBrightness(float floodLightmA = 200.0f); + void setOutputMode(int outputMode = 0); + void setDepthProfile(int confThreshold = 200, int lrcThreshold = 5); + void setRectification(bool useSpecTranslation, float alphaScaling = 0.0f); + void setIMU(bool imuPublished, bool publishInterIMU); + void setIrBrightness(float dotProjectormA = 0.0f, float floodLightmA = 200.0f); void setDetectFeatures(int detectFeatures = 0); void setBlobPath(const std::string & blobPath); void setGFTTDetector(bool useHarrisDetector = false, float minDistance = 7.0f, int numTargetFeatures = 1000); @@ -80,8 +78,9 @@ class RTABMAP_CORE_EXPORT CameraDepthAI : cv::Size targetSize_; Transform imuLocalTransform_; std::string mxidOrName_; - bool outputDepth_; - int depthConfidence_; + int outputMode_; + int confThreshold_; + int lrcThreshold_; int resolution_; bool useSpecTranslation_; float alphaScaling_; @@ -98,7 +97,7 @@ class RTABMAP_CORE_EXPORT CameraDepthAI : int nmsRadius_; std::string blobPath_; std::shared_ptr device_; - std::shared_ptr leftQueue_; + std::shared_ptr leftOrColorQueue_; std::shared_ptr rightOrDepthQueue_; std::shared_ptr featuresQueue_; std::map accBuffer_; diff --git a/corelib/src/camera/CameraDepthAI.cpp b/corelib/src/camera/CameraDepthAI.cpp index a3a21f217e..0d475fc8a9 100644 --- a/corelib/src/camera/CameraDepthAI.cpp +++ b/corelib/src/camera/CameraDepthAI.cpp @@ -54,8 +54,9 @@ CameraDepthAI::CameraDepthAI( #ifdef RTABMAP_DEPTHAI , mxidOrName_(mxidOrName), - outputDepth_(false), - depthConfidence_(200), + outputMode_(0), + confThreshold_(200), + lrcThreshold_(5), resolution_(resolution), useSpecTranslation_(false), alphaScaling_(0.0), @@ -87,67 +88,49 @@ CameraDepthAI::~CameraDepthAI() #endif } -void CameraDepthAI::setOutputDepth(bool enabled, int confidence) +void CameraDepthAI::setOutputMode(int outputMode) { #ifdef RTABMAP_DEPTHAI - outputDepth_ = enabled; - if(outputDepth_) - { - depthConfidence_ = confidence; - } + outputMode_ = outputMode; #else UERROR("CameraDepthAI: RTAB-Map is not built with depthai-core support!"); #endif } -void CameraDepthAI::setUseSpecTranslation(bool useSpecTranslation) +void CameraDepthAI::setDepthProfile(int confThreshold, int lrcThreshold) { #ifdef RTABMAP_DEPTHAI - useSpecTranslation_ = useSpecTranslation; + confThreshold_ = confThreshold; + lrcThreshold_ = lrcThreshold; #else UERROR("CameraDepthAI: RTAB-Map is not built with depthai-core support!"); #endif } -void CameraDepthAI::setAlphaScaling(float alphaScaling) +void CameraDepthAI::setRectification(bool useSpecTranslation, float alphaScaling) { #ifdef RTABMAP_DEPTHAI + useSpecTranslation_ = useSpecTranslation; alphaScaling_ = alphaScaling; #else UERROR("CameraDepthAI: RTAB-Map is not built with depthai-core support!"); #endif } -void CameraDepthAI::setIMUPublished(bool published) -{ -#ifdef RTABMAP_DEPTHAI - imuPublished_ = published; -#else - UERROR("CameraDepthAI: RTAB-Map is not built with depthai-core support!"); -#endif -} - -void CameraDepthAI::publishInterIMU(bool enabled) +void CameraDepthAI::setIMU(bool imuPublished, bool publishInterIMU) { #ifdef RTABMAP_DEPTHAI - publishInterIMU_ = enabled; + imuPublished_ = imuPublished; + publishInterIMU_ = publishInterIMU; #else UERROR("CameraDepthAI: RTAB-Map is not built with depthai-core support!"); #endif } -void CameraDepthAI::setLaserDotBrightness(float dotProjectormA) +void CameraDepthAI::setIrBrightness(float dotProjectormA, float floodLightmA) { #ifdef RTABMAP_DEPTHAI dotProjectormA_ = dotProjectormA; -#else - UERROR("CameraDepthAI: RTAB-Map is not built with depthai-core support!"); -#endif -} - -void CameraDepthAI::setFloodLightBrightness(float floodLightmA) -{ -#ifdef RTABMAP_DEPTHAI floodLightmA_ = floodLightmA; #else UERROR("CameraDepthAI: RTAB-Map is not built with depthai-core support!"); @@ -237,6 +220,16 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin auto monoLeft = p.create(); auto monoRight = p.create(); auto stereo = p.create(); + std::shared_ptr colorCam; + if(outputMode_==2) + { + colorCam = p.create(); + if(detectFeatures_) + { + UWARN("On-device feature detectors cannot be enabled on color camera input!"); + detectFeatures_ = 0; + } + } std::shared_ptr imu; if(imuPublished_) imu = p.create(); @@ -261,7 +254,7 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin } } - auto xoutLeft = p.create(); + auto xoutLeftOrColor = p.create(); auto xoutDepthOrRight = p.create(); std::shared_ptr xoutIMU; if(imuPublished_) @@ -271,17 +264,16 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin xoutFeatures = p.create(); // XLinkOut - xoutLeft->setStreamName("rectified_left"); - xoutDepthOrRight->setStreamName(outputDepth_?"depth":"rectified_right"); + xoutLeftOrColor->setStreamName(outputMode_<2?"rectified_left":"rectified_color"); + xoutDepthOrRight->setStreamName(outputMode_?"depth":"rectified_right"); if(imuPublished_) xoutIMU->setStreamName("imu"); if(detectFeatures_) xoutFeatures->setStreamName("features"); - // MonoCamera monoLeft->setResolution((dai::MonoCameraProperties::SensorResolution)resolution_); - monoLeft->setCamera("left"); monoRight->setResolution((dai::MonoCameraProperties::SensorResolution)resolution_); + monoLeft->setCamera("left"); monoRight->setCamera("right"); if(detectFeatures_ == 2) { @@ -299,17 +291,20 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin } // StereoDepth - stereo->setDepthAlign(dai::StereoDepthProperties::DepthAlign::RECTIFIED_LEFT); + if(outputMode_ == 2) + stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A); + else + stereo->setDepthAlign(dai::StereoDepthProperties::DepthAlign::RECTIFIED_LEFT); stereo->setExtendedDisparity(false); stereo->setRectifyEdgeFillColor(0); // black, to better see the cutout stereo->enableDistortionCorrection(true); stereo->setDisparityToDepthUseSpecTranslation(useSpecTranslation_); stereo->setDepthAlignmentUseSpecTranslation(useSpecTranslation_); - if(alphaScaling_>-1.0f) + if(alphaScaling_ > -1.0f) stereo->setAlphaScaling(alphaScaling_); - stereo->initialConfig.setConfidenceThreshold(depthConfidence_); + stereo->initialConfig.setConfidenceThreshold(confThreshold_); stereo->initialConfig.setLeftRightCheck(true); - stereo->initialConfig.setLeftRightCheckThreshold(5); + stereo->initialConfig.setLeftRightCheckThreshold(lrcThreshold_); stereo->initialConfig.setMedianFilter(dai::MedianFilter::KERNEL_7x7); auto config = stereo->initialConfig.get(); config.censusTransform.kernelSize = dai::StereoDepthConfig::CensusTransform::KernelSize::KERNEL_7x9; @@ -321,15 +316,32 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin monoLeft->out.link(stereo->left); monoRight->out.link(stereo->right); + if(outputMode_ == 2) + { + colorCam->setBoardSocket(dai::CameraBoardSocket::CAM_A); + colorCam->setSize(targetSize_.width, targetSize_.height); + if(this->getImageRate() > 0) + colorCam->setFps(this->getImageRate()); + if(alphaScaling_ > -1.0f) + colorCam->setCalibrationAlpha(alphaScaling_); + } + // Using VideoEncoder on PoE devices, Subpixel is not supported if(deviceToUse.protocol == X_LINK_TCP_IP || mxidOrName_.find(".") != std::string::npos) { - auto leftEnc = p.create(); + auto leftOrColorEnc = p.create(); auto depthOrRightEnc = p.create(); - leftEnc->setDefaultProfilePreset(monoLeft->getFps(), dai::VideoEncoderProperties::Profile::MJPEG); + leftOrColorEnc->setDefaultProfilePreset(monoLeft->getFps(), dai::VideoEncoderProperties::Profile::MJPEG); depthOrRightEnc->setDefaultProfilePreset(monoRight->getFps(), dai::VideoEncoderProperties::Profile::MJPEG); - stereo->rectifiedLeft.link(leftEnc->input); - if(outputDepth_) + if(outputMode_ < 2) + { + stereo->rectifiedLeft.link(leftOrColorEnc->input); + } + else + { + colorCam->video.link(leftOrColorEnc->input); + } + if(outputMode_) { depthOrRightEnc->setQuality(100); stereo->disparity.link(depthOrRightEnc->input); @@ -338,7 +350,7 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin { stereo->rectifiedRight.link(depthOrRightEnc->input); } - leftEnc->bitstream.link(xoutLeft->input); + leftOrColorEnc->bitstream.link(xoutLeftOrColor->input); depthOrRightEnc->bitstream.link(xoutDepthOrRight->input); } else @@ -349,8 +361,17 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin config.costMatching.disparityWidth = dai::StereoDepthConfig::CostMatching::DisparityWidth::DISPARITY_64; config.costMatching.enableCompanding = true; stereo->initialConfig.set(config); - stereo->rectifiedLeft.link(xoutLeft->input); - if(outputDepth_) + if(outputMode_ < 2) + { + stereo->rectifiedLeft.link(xoutLeftOrColor->input); + } + else + { + monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); + monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); + colorCam->video.link(xoutLeftOrColor->input); + } + if(outputMode_) stereo->depth.link(xoutDepthOrRight->input); else stereo->rectifiedRight.link(xoutDepthOrRight->input); @@ -403,30 +424,34 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin UINFO("Loading eeprom calibration data"); dai::CalibrationHandler calibHandler = device_->readCalibration(); - cv::Mat cameraMatrix, distCoeffs, new_camera_matrix; + auto cameraId = outputMode_<2?dai::CameraBoardSocket::CAM_B:dai::CameraBoardSocket::CAM_A; + cv::Mat cameraMatrix, distCoeffs, newCameraMatrix; - std::vector > matrix = calibHandler.getCameraIntrinsics(dai::CameraBoardSocket::CAM_B, dai::Size2f(targetSize_.width, targetSize_.height)); + std::vector > matrix = calibHandler.getCameraIntrinsics(cameraId, targetSize_.width, targetSize_.height); cameraMatrix = (cv::Mat_(3,3) << matrix[0][0], matrix[0][1], matrix[0][2], matrix[1][0], matrix[1][1], matrix[1][2], matrix[2][0], matrix[2][1], matrix[2][2]); - std::vector coeffs = calibHandler.getDistortionCoefficients(dai::CameraBoardSocket::CAM_B); - if(calibHandler.getDistortionModel(dai::CameraBoardSocket::CAM_B) == dai::CameraModel::Perspective) + std::vector coeffs = calibHandler.getDistortionCoefficients(cameraId); + if(calibHandler.getDistortionModel(cameraId) == dai::CameraModel::Perspective) distCoeffs = (cv::Mat_(1,8) << coeffs[0], coeffs[1], coeffs[2], coeffs[3], coeffs[4], coeffs[5], coeffs[6], coeffs[7]); if(alphaScaling_>-1.0f) - new_camera_matrix = cv::getOptimalNewCameraMatrix(cameraMatrix, distCoeffs, targetSize_, alphaScaling_); + newCameraMatrix = cv::getOptimalNewCameraMatrix(cameraMatrix, distCoeffs, targetSize_, alphaScaling_); else - new_camera_matrix = cameraMatrix; + newCameraMatrix = cameraMatrix; - double fx = new_camera_matrix.at(0, 0); - double fy = new_camera_matrix.at(1, 1); - double cx = new_camera_matrix.at(0, 2); - double cy = new_camera_matrix.at(1, 2); + double fx = newCameraMatrix.at(0, 0); + double fy = newCameraMatrix.at(1, 1); + double cx = newCameraMatrix.at(0, 2); + double cy = newCameraMatrix.at(1, 2); double baseline = calibHandler.getBaselineDistance(dai::CameraBoardSocket::CAM_C, dai::CameraBoardSocket::CAM_B, useSpecTranslation_)/100.0; - UINFO("left: fx=%f fy=%f cx=%f cy=%f baseline=%f", fx, fy, cx, cy, baseline); - stereoModel_ = StereoCameraModel(device_->getDeviceName(), fx, fy, cx, cy, baseline, this->getLocalTransform(), targetSize_); + UINFO("fx=%f fy=%f cx=%f cy=%f baseline=%f", fx, fy, cx, cy, baseline); + if(outputMode_ == 2) + stereoModel_ = StereoCameraModel(device_->getDeviceName(), fx, fy, cx, cy, baseline, this->getLocalTransform(), targetSize_); + else + stereoModel_ = StereoCameraModel(device_->getDeviceName(), fx, fy, cx, cy, baseline, this->getLocalTransform()*Transform(-calibHandler.getBaselineDistance(dai::CameraBoardSocket::CAM_A)/100.0, 0, 0), targetSize_); if(imuPublished_) { @@ -443,22 +468,29 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin { imuLocalTransform_ = Transform( 0, -1, 0, 0.0525, - 1, 0, 0, 0.0137, + 1, 0, 0, 0.013662, 0, 0, 1, 0); } else if(eeprom.boardName == "DM9098") { imuLocalTransform_ = Transform( - 0, 1, 0, 0.075445, + 0, 1, 0, 0.037945, 1, 0, 0, 0.00079, - 0, 0, -1, -0.007); + 0, 0, -1, 0); + } + else if(eeprom.boardName == "NG2094") + { + imuLocalTransform_ = Transform( + 0, 1, 0, 0.0374, + 1, 0, 0, 0.00176, + 0, 0, -1, 0); } else if(eeprom.boardName == "NG9097") { imuLocalTransform_ = Transform( - 0, 1, 0, 0.0775, + 0, 1, 0, 0.04, 1, 0, 0, 0.020265, - 0, 0, -1, -0.007); + 0, 0, -1, 0); } else { @@ -502,8 +534,8 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin } }); } - leftQueue_ = device_->getOutputQueue("rectified_left", 8, false); - rightOrDepthQueue_ = device_->getOutputQueue(outputDepth_?"depth":"rectified_right", 8, false); + leftOrColorQueue_ = device_->getOutputQueue(outputMode_<2?"rectified_left":"rectified_color", 8, false); + rightOrDepthQueue_ = device_->getOutputQueue(outputMode_?"depth":"rectified_right", 8, false); if(detectFeatures_) featuresQueue_ = device_->getOutputQueue("features", 8, false); @@ -545,21 +577,21 @@ SensorData CameraDepthAI::captureImage(CameraInfo * info) SensorData data; #ifdef RTABMAP_DEPTHAI - cv::Mat left, depthOrRight; - auto rectifL = leftQueue_->get(); + cv::Mat leftOrColor, depthOrRight; + auto rectifLeftOrColor = leftOrColorQueue_->get(); auto rectifRightOrDepth = rightOrDepthQueue_->get(); - while(rectifL->getSequenceNum() < rectifRightOrDepth->getSequenceNum()) - rectifL = leftQueue_->get(); - while(rectifL->getSequenceNum() > rectifRightOrDepth->getSequenceNum()) + while(rectifLeftOrColor->getSequenceNum() < rectifRightOrDepth->getSequenceNum()) + rectifLeftOrColor = leftOrColorQueue_->get(); + while(rectifLeftOrColor->getSequenceNum() > rectifRightOrDepth->getSequenceNum()) rectifRightOrDepth = rightOrDepthQueue_->get(); - double stamp = std::chrono::duration(rectifL->getTimestampDevice(dai::CameraExposureOffset::MIDDLE).time_since_epoch()).count(); + double stamp = std::chrono::duration(rectifLeftOrColor->getTimestampDevice(dai::CameraExposureOffset::MIDDLE).time_since_epoch()).count(); if(device_->getDeviceInfo().protocol == X_LINK_TCP_IP || mxidOrName_.find(".") != std::string::npos) { - left = cv::imdecode(rectifL->getData(), cv::IMREAD_GRAYSCALE); + leftOrColor = cv::imdecode(rectifLeftOrColor->getData(), cv::IMREAD_ANYCOLOR); depthOrRight = cv::imdecode(rectifRightOrDepth->getData(), cv::IMREAD_GRAYSCALE); - if(outputDepth_) + if(outputMode_) { cv::Mat disp; depthOrRight.convertTo(disp, CV_16UC1); @@ -568,14 +600,14 @@ SensorData CameraDepthAI::captureImage(CameraInfo * info) } else { - left = rectifL->getFrame(true); - depthOrRight = rectifRightOrDepth->getFrame(true); + leftOrColor = rectifLeftOrColor->getCvFrame(); + depthOrRight = rectifRightOrDepth->getCvFrame(); } - if(outputDepth_) - data = SensorData(left, depthOrRight, stereoModel_.left(), this->getNextSeqID(), stamp); + if(outputMode_) + data = SensorData(leftOrColor, depthOrRight, stereoModel_.left(), this->getNextSeqID(), stamp); else - data = SensorData(left, depthOrRight, stereoModel_, this->getNextSeqID(), stamp); + data = SensorData(leftOrColor, depthOrRight, stereoModel_, this->getNextSeqID(), stamp); if(imuPublished_ && !publishInterIMU_) { @@ -629,7 +661,7 @@ SensorData CameraDepthAI::captureImage(CameraInfo * info) if(detectFeatures_ == 1) { auto features = featuresQueue_->get(); - while(features->getSequenceNum() < rectifL->getSequenceNum()) + while(features->getSequenceNum() < rectifLeftOrColor->getSequenceNum()) features = featuresQueue_->get(); auto detectedFeatures = features->trackedFeatures; @@ -641,7 +673,7 @@ SensorData CameraDepthAI::captureImage(CameraInfo * info) else if(detectFeatures_ == 2) { auto features = featuresQueue_->get(); - while(features->getSequenceNum() < rectifL->getSequenceNum()) + while(features->getSequenceNum() < rectifLeftOrColor->getSequenceNum()) features = featuresQueue_->get(); auto heatmap = features->getLayerFp16("heatmap"); diff --git a/guilib/src/PreferencesDialog.cpp b/guilib/src/PreferencesDialog.cpp index be43c11164..b9701c57fd 100644 --- a/guilib/src/PreferencesDialog.cpp +++ b/guilib/src/PreferencesDialog.cpp @@ -804,8 +804,9 @@ PreferencesDialog::PreferencesDialog(QWidget * parent) : connect(_ui->spinBox_stereoMyntEye_irControl, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel())); connect(_ui->comboBox_depthai_resolution, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel())); - connect(_ui->checkBox_depthai_depth, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel())); - connect(_ui->spinBox_depthai_confidence, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel())); + connect(_ui->comboBox_depthai_output_mode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel())); + connect(_ui->spinBox_depthai_conf_threshold, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel())); + connect(_ui->spinBox_depthai_lrc_threshold, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel())); connect(_ui->checkBox_depthai_use_spec_translation, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel())); connect(_ui->doubleSpinBox_depthai_alpha_scaling, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel())); connect(_ui->checkBox_depthai_imu_published, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel())); @@ -2142,8 +2143,9 @@ void PreferencesDialog::resetSettings(QGroupBox * groupBox) _ui->spinBox_stereoMyntEye_contrast->setValue(116); _ui->spinBox_stereoMyntEye_irControl->setValue(0); _ui->comboBox_depthai_resolution->setCurrentIndex(1); - _ui->checkBox_depthai_depth->setChecked(false); - _ui->spinBox_depthai_confidence->setValue(200); + _ui->comboBox_depthai_output_mode->setCurrentIndex(0); + _ui->spinBox_depthai_conf_threshold->setValue(200); + _ui->spinBox_depthai_lrc_threshold->setValue(5); _ui->checkBox_depthai_use_spec_translation->setChecked(false); _ui->doubleSpinBox_depthai_alpha_scaling->setValue(0.0); _ui->checkBox_depthai_imu_published->setChecked(true); @@ -2633,8 +2635,9 @@ void PreferencesDialog::readCameraSettings(const QString & filePath) settings.beginGroup("DepthAI"); _ui->comboBox_depthai_resolution->setCurrentIndex(settings.value("resolution", _ui->comboBox_depthai_resolution->currentIndex()).toInt()); - _ui->checkBox_depthai_depth->setChecked(settings.value("depth", _ui->checkBox_depthai_depth->isChecked()).toBool()); - _ui->spinBox_depthai_confidence->setValue(settings.value("confidence", _ui->spinBox_depthai_confidence->value()).toInt()); + _ui->comboBox_depthai_output_mode->setCurrentIndex(settings.value("output_mode", _ui->comboBox_depthai_output_mode->currentIndex()).toInt()); + _ui->spinBox_depthai_conf_threshold->setValue(settings.value("conf_threshold", _ui->spinBox_depthai_conf_threshold->value()).toInt()); + _ui->spinBox_depthai_lrc_threshold->setValue(settings.value("lrc_threshold", _ui->spinBox_depthai_lrc_threshold->value()).toInt()); _ui->checkBox_depthai_use_spec_translation->setChecked(settings.value("use_spec_translation", _ui->checkBox_depthai_use_spec_translation->isChecked()).toBool()); _ui->doubleSpinBox_depthai_alpha_scaling->setValue(settings.value("alpha_scaling", _ui->doubleSpinBox_depthai_alpha_scaling->value()).toDouble()); _ui->checkBox_depthai_imu_published->setChecked(settings.value("imu_published", _ui->checkBox_depthai_imu_published->isChecked()).toBool()); @@ -3167,8 +3170,9 @@ void PreferencesDialog::writeCameraSettings(const QString & filePath) const settings.beginGroup("DepthAI"); settings.setValue("resolution", _ui->comboBox_depthai_resolution->currentIndex()); - settings.setValue("depth", _ui->checkBox_depthai_depth->isChecked()); - settings.setValue("confidence", _ui->spinBox_depthai_confidence->value()); + settings.setValue("output_mode", _ui->comboBox_depthai_output_mode->currentIndex()); + settings.setValue("conf_threshold", _ui->spinBox_depthai_conf_threshold->value()); + settings.setValue("lrc_threshold", _ui->spinBox_depthai_lrc_threshold->value()); settings.setValue("use_spec_translation", _ui->checkBox_depthai_use_spec_translation->isChecked()); settings.setValue("alpha_scaling", _ui->doubleSpinBox_depthai_alpha_scaling->value()); settings.setValue("imu_published", _ui->checkBox_depthai_imu_published->isChecked()); @@ -6486,13 +6490,11 @@ Camera * PreferencesDialog::createCamera( _ui->comboBox_depthai_resolution->currentIndex(), this->getGeneralInputRate(), this->getSourceLocalTransform()); - ((CameraDepthAI*)camera)->setOutputDepth(_ui->checkBox_depthai_depth->isChecked(), _ui->spinBox_depthai_confidence->value()); - ((CameraDepthAI*)camera)->setUseSpecTranslation(_ui->checkBox_depthai_use_spec_translation->isChecked()); - ((CameraDepthAI*)camera)->setAlphaScaling(_ui->doubleSpinBox_depthai_alpha_scaling->value()); - ((CameraDepthAI*)camera)->setIMUPublished(_ui->checkBox_depthai_imu_published->isChecked()); - ((CameraDepthAI*)camera)->publishInterIMU(_ui->checkbox_publishInterIMU->isChecked()); - ((CameraDepthAI*)camera)->setLaserDotBrightness(_ui->doubleSpinBox_depthai_laser_dot_brightness->value()); - ((CameraDepthAI*)camera)->setFloodLightBrightness(_ui->doubleSpinBox_depthai_floodlight_brightness->value()); + ((CameraDepthAI*)camera)->setOutputMode(_ui->comboBox_depthai_output_mode->currentIndex()); + ((CameraDepthAI*)camera)->setDepthProfile(_ui->spinBox_depthai_conf_threshold->value(), _ui->spinBox_depthai_lrc_threshold->value()); + ((CameraDepthAI*)camera)->setRectification(_ui->checkBox_depthai_use_spec_translation->isChecked(), _ui->doubleSpinBox_depthai_alpha_scaling->value()); + ((CameraDepthAI*)camera)->setIMU(_ui->checkBox_depthai_imu_published->isChecked(), _ui->checkbox_publishInterIMU->isChecked()); + ((CameraDepthAI*)camera)->setIrBrightness(_ui->doubleSpinBox_depthai_laser_dot_brightness->value(), _ui->doubleSpinBox_depthai_floodlight_brightness->value()); ((CameraDepthAI*)camera)->setDetectFeatures(_ui->comboBox_depthai_detect_features->currentIndex()); ((CameraDepthAI*)camera)->setBlobPath(_ui->lineEdit_depthai_blob_path->text().toStdString()); if(_ui->comboBox_depthai_detect_features->currentIndex() == 1) diff --git a/guilib/src/ui/preferencesDialog.ui b/guilib/src/ui/preferencesDialog.ui index 283f69af30..e381af3a85 100644 --- a/guilib/src/ui/preferencesDialog.ui +++ b/guilib/src/ui/preferencesDialog.ui @@ -5905,7 +5905,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + -1.000000000000000 @@ -5924,7 +5924,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - Depth confidence. + Confidence threshold. true @@ -5934,7 +5934,20 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + + + + Left-right check threshold. + + + true + + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + + + + mA @@ -5947,14 +5960,14 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + - + Floodlight brightness. @@ -5967,7 +5980,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + Laser dot brightness. @@ -5980,7 +5993,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + Use the translation information from the board design data (not the calibration data). @@ -6007,13 +6020,31 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - - - + + + 0 + + QComboBox::AdjustToContents + + + + Stereo + + + + + Mono+Depth + + + + + Color+Depth + + - + Free scaling parameter between 0 (when all the pixels in the undistorted image are valid) and 1 (when all the source image pixels are retained in the undistorted image). On some high distortion lenses, and/or due to rectification (image rotated) invalid areas may appear even with alpha=0, in these cases alpha < 0.0 helps removing invalid areas. If alpha is set to -1, old rectification policy is used. @@ -6027,7 +6058,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + 0 @@ -6039,7 +6070,20 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + + + + 0 + + + 255 + + + 5 + + + + IMU published @@ -6052,7 +6096,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + @@ -6062,7 +6106,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - Output depth. + Output mode. true @@ -6072,7 +6116,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + mA @@ -6085,7 +6129,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + 0 @@ -6110,7 +6154,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + On-device feature detector. @@ -6123,7 +6167,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + @@ -6147,7 +6191,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki - + Path to SuperPoint blob file.