diff --git a/corelib/src/camera/CameraK4A.cpp b/corelib/src/camera/CameraK4A.cpp
index 73f47836e2..fffd90b69b 100644
--- a/corelib/src/camera/CameraK4A.cpp
+++ b/corelib/src/camera/CameraK4A.cpp
@@ -286,8 +286,6 @@ bool CameraK4A::init(const std::string & calibrationFolder, const std::string &
cv::Size(calibration_.depth_camera_calibration.resolution_width, calibration_.depth_camera_calibration.resolution_height),
K,D,R,P,
this->getLocalTransform());
- UASSERT(model_.isValidForRectification());
- model_.initRectificationMap();
}
else
{
@@ -317,6 +315,8 @@ bool CameraK4A::init(const std::string & calibrationFolder, const std::string &
K,D,R,P,
this->getLocalTransform());
}
+ UASSERT(model_.isValidForRectification());
+ model_.initRectificationMap();
if (ULogger::level() <= ULogger::kInfo)
{
@@ -490,6 +490,7 @@ SensorData CameraK4A::captureImage(CameraInfo * info)
cv::cvtColor(bgra, bgrCV, CV_BGRA2BGR);
}
+ bgrCV = model_.rectifyImage(bgrCV);
// Release the image
k4a_image_release(rgb_image_);
diff --git a/guilib/src/ui/preferencesDialog.ui b/guilib/src/ui/preferencesDialog.ui
index 9f621a4af1..2ea46cdcd6 100644
--- a/guilib/src/ui/preferencesDialog.ui
+++ b/guilib/src/ui/preferencesDialog.ui
@@ -63,7 +63,7 @@
0
- 0
+ -677
686
3286
@@ -95,7 +95,7 @@
QFrame::Raised
- 10
+ 5
@@ -3220,7 +3220,7 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki
-
- 9
+ 10
@@ -4476,6 +4476,9 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki
Frames per second
+
+ Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse
+
-
@@ -4567,11 +4570,14 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki
-
- Use IR for RGB image (odometry may be better)
+ Use IR for RGB image (may work better in dark areas).
true
+
+ Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse
+
-
@@ -4606,12 +4612,21 @@ when using the file type, logs are saved in LogRtabmap.txt (located in the worki
true
+
+ Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse
+
-
- RGB camera resolution
+ <html><head/><body><p>RGB camera resolution. Note that when color camera is used (IR mode is not checked below), to <span style=" font-weight:600;">avoid black borders in point clouds</span> generated, set ROI ratios under 3D Rendering settings to "0.05 0.05 0.05 0.05" under Map and Odom columns.</p></body></html>
+
+
+ true
+
+
+ Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse