Skip to content

Commit

Permalink
reduce depth image noise and simplify calculation for compressed tran…
Browse files Browse the repository at this point in the history
…sport
  • Loading branch information
borongyuan committed Oct 7, 2023
1 parent 93637f8 commit 46042ce
Showing 1 changed file with 8 additions and 5 deletions.
13 changes: 8 additions & 5 deletions corelib/src/camera/CameraDepthAI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -343,9 +343,14 @@ bool CameraDepthAI::init(const std::string & calibrationFolder, const std::strin
depthOrRightEnc->setDefaultProfilePreset(monoRight->getFps(), dai::VideoEncoderProperties::Profile::MJPEG);
stereo->rectifiedLeft.link(leftEnc->input);
if(outputDepth_)
{
depthOrRightEnc->setQuality(100);
stereo->disparity.link(depthOrRightEnc->input);
}
else
{
stereo->rectifiedRight.link(depthOrRightEnc->input);
}
leftEnc->bitstream.link(xoutLeft->input);
depthOrRightEnc->bitstream.link(xoutDepthOrRight->input);
}
Expand Down Expand Up @@ -569,11 +574,9 @@ SensorData CameraDepthAI::captureImage(CameraInfo * info)
depthOrRight = cv::imdecode(rectifRightOrDepth->getData(), cv::IMREAD_GRAYSCALE);
if(outputDepth_)
{
cv::Mat depth(targetSize_, CV_16UC1);
depth.forEach<uint16_t>([&](uint16_t& pixel, const int * position) -> void {
pixel = stereoModel_.computeDepth(depthOrRight.at<uint8_t>(position))*1000;
});
depthOrRight = depth;
cv::Mat disp;
depthOrRight.convertTo(disp, CV_16UC1);
cv::divide(-stereoModel_.right().Tx() * 1000, disp, depthOrRight);
}
}
else
Expand Down

0 comments on commit 46042ce

Please sign in to comment.