Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixes and improvements for StereoDepth, ColorCamera #82

Merged
merged 32 commits into from
Apr 28, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
32 commits
Select commit Hold shift + click to select a range
db02740
ColorCamera: add `isp`, `raw` outputs
alex-luxonis Jan 7, 2021
ea9a98b
ColorCamera: add setIspScale/setIspScaleFull API
alex-luxonis Feb 11, 2021
0431b74
StereoDepth: deprecate setOutputDepth/Rectified
alex-luxonis Mar 9, 2021
5f2f312
ColorCamera: add API to get 'isp' scaled output size
alex-luxonis Mar 9, 2021
e04b257
`make clangformat`
alex-luxonis Mar 9, 2021
2f9ad0a
Update FW: stereo fixes, stereo/ColorCamera improvements
alex-luxonis Mar 9, 2021
f22ca12
Add API to configure disparity/depth alignment: left/right/center.
alex-luxonis Mar 13, 2021
4fc1433
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Mar 25, 2021
974dc98
StereoDepth: add overloaded setDepthAlign(CameraBoardSocket)
alex-luxonis Mar 25, 2021
4ec7f1f
StereoDepth: remove for now 'setBaselineOverrideCm', 'setFovOverrideD…
alex-luxonis Mar 25, 2021
ca3784b
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Mar 30, 2021
69726b3
Update FW: disparity (U8) aligning to RGB works.
alex-luxonis Mar 31, 2021
f809bb6
Address review comments:
alex-luxonis Mar 31, 2021
d4338e2
CameraControl: add ranges for extra controls,
alex-luxonis Mar 23, 2021
8c3a8e6
Add rgb_depth_aligned example
alex-luxonis Apr 1, 2021
29ca1c5
Fix conversion of YUV420p frames to OpenCV BGR,
alex-luxonis Apr 1, 2021
757d830
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Apr 1, 2021
3964a7e
Examples: remove deprecated API setOutputDepth/Rectified
alex-luxonis Apr 1, 2021
fefb4b0
GitHub CI: limit cmake --parallel to 8 threads,
alex-luxonis Apr 1, 2021
878e4a6
README build snippets: limit `cmake --parallel` to 8
alex-luxonis Apr 1, 2021
b72bb07
Cleanup, remove some unused variables
alex-luxonis Apr 1, 2021
7df7402
Update FW: optimize depth align, make it work with subpixel/U16
alex-luxonis Apr 2, 2021
df43775
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Apr 19, 2021
b0dd5d6
stereo_example: rectified flip no longer needed with LR-check on,
alex-luxonis Apr 21, 2021
6e11c1f
spatial_object_tracker example: remove deprecated setOutputDepth
alex-luxonis Apr 21, 2021
1e05f8c
fixed getting size of video/still when setting isp scaling
Erol444 Apr 24, 2021
3f2fb9d
Address review comments. Note:
alex-luxonis Apr 28, 2021
6d84ac9
clangformat cleanup
alex-luxonis Apr 27, 2021
f62304d
Update FW: fix still capture with scaling, add FPS capping (with warn…
alex-luxonis Apr 27, 2021
2e25a1e
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Apr 28, 2021
bf1cbdd
Update FW: fix ImageManip U16 crop (for depth/subpixel disparity)
alex-luxonis Apr 28, 2021
bffa915
Update FW, fix CI build: depthai-shared PR merged
alex-luxonis Apr 28, 2021
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 6 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,27 +43,28 @@ Make sure submodules are updated
```
git submodule update --init --recursive
```
ℹ️ For the `--parallel` argument of the commands below, specify a value `[num CPU cores]` or less, to reduce memory consumption during build. E.g.: `--parallel 8`

**Static library**
```
mkdir build && cd build
cmake ..
cmake --build . --parallel 8
cmake --build . --parallel
```

**Dynamic library**
```
mkdir build && cd build
cmake .. -D BUILD_SHARED_LIBS=ON
cmake --build . --parallel 8
cmake --build . --parallel
```
## Installing

To install specify optional prefix and build target install
```
cmake .. -D CMAKE_INSTALL_PREFIX=[path/to/install/dir]
cmake --build . --parallel 8
cmake --build . --target install --parallel 8
cmake --build . --parallel
cmake --build . --target install --parallel
```

## Running tests
Expand All @@ -72,7 +73,7 @@ To run the tests build the library with the following options
```
mkdir build_tests && cd build_tests
cmake .. -D DEPTHAI_TEST_EXAMPLES=ON -D DEPTHAI_BUILD_TESTS=ON -D DEPTHAI_BUILD_EXAMPLES=ON
cmake --build . --parallel 8
cmake --build . --parallel
ctest
```

Expand Down
2 changes: 1 addition & 1 deletion cmake/Depthai/DepthaiDeviceSideConfig.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot")

# "full commit hash of device side binary"
set(DEPTHAI_DEVICE_SIDE_COMMIT "b71584129b101b30e4632678c19d33b020c04c36")
set(DEPTHAI_DEVICE_SIDE_COMMIT "3b51648b0d96c9391d878eede0fd5fd9b44084ca")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
3 changes: 3 additions & 0 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,9 @@ dai_add_example(device_queue_event src/device_queue_event_example.cpp)
# OpenCV support example
dai_add_example(opencv_support src/opencv_support_example.cpp)

# RGB-depth alignment example
dai_add_example(rgb_depth_aligned src/rgb_depth_aligned_example.cpp)

# Device side decoding example for mobilenet-ssd
dai_add_example(mobilenet_device_side_decoding src/mobilenet_device_side_decoding_example.cpp)
target_compile_definitions(mobilenet_device_side_decoding PRIVATE BLOB_PATH="${mobilenet_blob}")
Expand Down
110 changes: 110 additions & 0 deletions examples/src/rgb_depth_aligned_example.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
#include <cstdio>
#include <iostream>

#include "utility.hpp"

// Includes common necessary includes for development using depthai library
#include "depthai/depthai.hpp"

// Optional. If set (true), the ColorCamera is downscaled from 1080p to 720p.
// Otherwise (false), the aligned depth is automatically upscaled to 1080p
static constexpr bool downscaleColor = true;

int main() {
using namespace std;

dai::Pipeline p;
std::vector<std::string> queueNames;

auto cam = p.create<dai::node::ColorCamera>();
cam->setBoardSocket(dai::CameraBoardSocket::RGB);
cam->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P);
if(downscaleColor) cam->setIspScale(2, 3);
// For now, RGB needs fixed focus to properly align with depth.
// This value was used during calibration
cam->initialControl.setManualFocus(130);

auto rgbOut = p.create<dai::node::XLinkOut>();
rgbOut->setStreamName("rgb");
queueNames.push_back("rgb");
cam->isp.link(rgbOut->input);

auto left = p.create<dai::node::MonoCamera>();
left->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P);
left->setBoardSocket(dai::CameraBoardSocket::LEFT);

auto right = p.create<dai::node::MonoCamera>();
right->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P);
right->setBoardSocket(dai::CameraBoardSocket::RIGHT);

auto stereo = p.create<dai::node::StereoDepth>();
stereo->setConfidenceThreshold(200);
// LR-check is required for depth alignment
stereo->setLeftRightCheck(true);
stereo->setDepthAlign(dai::CameraBoardSocket::RGB);
left->out.link(stereo->left);
right->out.link(stereo->right);

auto depthOut = p.create<dai::node::XLinkOut>();
depthOut->setStreamName("depth");
queueNames.push_back("depth");
// Currently we use the 'disparity' output. TODO 'depth'
stereo->disparity.link(depthOut->input);

// Connect to device
dai::Device d(p);
d.startPipeline();

// Sets queues size and behavior
for(const auto& name : queueNames) {
d.getOutputQueue(name, 4, false);
}

std::unordered_map<std::string, cv::Mat> frame;

while(1) {
std::unordered_map<std::string, std::shared_ptr<dai::ImgFrame>> latestPacket;

auto queueEvents = d.getQueueEvents(queueNames);
for(const auto& name : queueEvents) {
auto packets = d.getOutputQueue(name)->tryGetAll<dai::ImgFrame>();
auto count = packets.size();
if(count > 0) {
latestPacket[name] = packets[count - 1];
}
}

for(const auto& name : queueNames) {
if(latestPacket.find(name) != latestPacket.end()) {
if(name == "depth") {
frame[name] = latestPacket[name]->getFrame();
// Optional, extend range 0..95 -> 0..255, for a better visualisation
if(1) frame[name].convertTo(frame[name], CV_8UC1, 255. / 95);
// Optional, apply false colorization
if(1) cv::applyColorMap(frame[name], frame[name], cv::COLORMAP_HOT);
} else {
frame[name] = latestPacket[name]->getCvFrame();
}

cv::imshow(name, frame[name]);
}
}

// Blend when both received
if(frame.find("rgb") != frame.end() && frame.find("depth") != frame.end()) {
// Need to have both frames in BGR format before blending
if(frame["depth"].channels() < 3) {
cv::cvtColor(frame["depth"], frame["depth"], cv::COLOR_GRAY2BGR);
}
cv::Mat blended;
cv::addWeighted(frame["rgb"], 0.6, frame["depth"], 0.4, 0, blended);
cv::imshow("rgb-depth", blended);
frame.clear();
}

int key = cv::waitKey(1);
if(key == 'q') {
return 0;
}
}
}
4 changes: 0 additions & 4 deletions examples/src/spatial_location_calculator_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,10 @@ int main() {
monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT);

bool outputDepth = true;
bool outputRectified = false;
bool lrcheck = false;
bool subpixel = false;

// StereoDepth
stereo->setOutputDepth(outputDepth);
stereo->setOutputRectified(outputRectified);
stereo->setConfidenceThreshold(255);

// stereo->setMedianFilter(dai::StereoDepthProperties::MedianFilter::MEDIAN_OFF);
Expand Down
3 changes: 1 addition & 2 deletions examples/src/spatial_mobilenet_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ dai::Pipeline createNNPipeline(std::string nnPath) {
monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT);

/// setting node configs
stereo->setOutputDepth(true);
stereo->setConfidenceThreshold(255);

spatialDetectionNetwork->setBlobPath(nnPath);
Expand Down Expand Up @@ -189,4 +188,4 @@ int main(int argc, char** argv) {
}

return 0;
}
}
4 changes: 1 addition & 3 deletions examples/src/spatial_mobilenet_mono_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,6 @@ dai::Pipeline createNNPipeline(std::string nnPath) {
monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT);

// StereoDepth
stereo->setOutputDepth(true);
stereo->setOutputRectified(true);
stereo->setConfidenceThreshold(255);

// Link plugins CAM -> STEREO -> XLINK
Expand Down Expand Up @@ -199,4 +197,4 @@ int main(int argc, char** argv) {
}

return 0;
}
}
3 changes: 1 addition & 2 deletions examples/src/spatial_object_tracker_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ dai::Pipeline createNNPipeline(std::string nnPath) {
monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT);

/// setting node configs
stereo->setOutputDepth(true);
stereo->setConfidenceThreshold(255);

spatialDetectionNetwork->setBlobPath(nnPath);
Expand Down Expand Up @@ -168,4 +167,4 @@ int main(int argc, char** argv) {
}

return 0;
}
}
3 changes: 1 addition & 2 deletions examples/src/spatial_tiny_yolo_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,6 @@ dai::Pipeline createNNPipeline(std::string nnPath) {
monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT);

/// setting node configs
stereo->setOutputDepth(true);
stereo->setConfidenceThreshold(255);

spatialDetectionNetwork->setBlobPath(nnPath);
Expand Down Expand Up @@ -203,4 +202,4 @@ int main(int argc, char** argv) {
}

return 0;
}
}
22 changes: 5 additions & 17 deletions examples/src/stereo_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,6 @@ int main() {

if(withDepth) {
// StereoDepth
stereo->setOutputDepth(outputDepth);
stereo->setOutputRectified(outputRectified);
stereo->setConfidenceThreshold(200);
stereo->setRectifyEdgeFillColor(0); // black, to better see the cutout
// stereo->loadCalibrationFile("../../../../depthai/resources/depthai.calib");
Expand All @@ -79,7 +77,9 @@ int main() {
stereo->rectifiedRight.link(xoutRectifR->input);
}
stereo->disparity.link(xoutDisp->input);
stereo->depth.link(xoutDepth->input);
if (outputDepth) {
stereo->depth.link(xoutDepth->input);
}

} else {
// Link plugins CAM -> XLINK
Expand All @@ -99,15 +99,10 @@ int main() {
auto rectifRightQueue = withDepth ? d.getOutputQueue("rectified_right", 8, false) : nullptr;

while(1) {
auto t1 = steady_clock::now();
auto left = leftQueue->get<dai::ImgFrame>();
auto t2 = steady_clock::now();
cv::imshow("left", cv::Mat(left->getHeight(), left->getWidth(), CV_8UC1, left->getData().data()));
auto t3 = steady_clock::now();
auto right = rightQueue->get<dai::ImgFrame>();
auto t4 = steady_clock::now();
cv::imshow("right", cv::Mat(right->getHeight(), right->getWidth(), CV_8UC1, right->getData().data()));
auto t5 = steady_clock::now();

if(withDepth) {
// Note: in some configurations (if depth is enabled), disparity may output garbage data
Expand All @@ -127,24 +122,17 @@ int main() {
if(outputRectified) {
auto rectifL = rectifLeftQueue->get<dai::ImgFrame>();
cv::Mat rectifiedLeftFrame = rectifL->getFrame();
cv::flip(rectifiedLeftFrame, rectifiedLeftFrame, 1);
//cv::flip(rectifiedLeftFrame, rectifiedLeftFrame, 1);
cv::imshow("rectified_left", rectifiedLeftFrame);

auto rectifR = rectifRightQueue->get<dai::ImgFrame>();
cv::Mat rectifiedRightFrame = rectifR->getFrame();

cv::flip(rectifiedRightFrame, rectifiedRightFrame, 1);
//cv::flip(rectifiedRightFrame, rectifiedRightFrame, 1);
cv::imshow("rectified_right", rectifiedRightFrame);
}
}

int ms1 = std::chrono::duration_cast<std::chrono::milliseconds>(t2 - t1).count();
int ms2 = std::chrono::duration_cast<std::chrono::milliseconds>(t3 - t2).count();
int ms3 = std::chrono::duration_cast<std::chrono::milliseconds>(t4 - t3).count();
int ms4 = std::chrono::duration_cast<std::chrono::milliseconds>(t5 - t4).count();
int loop = std::chrono::duration_cast<std::chrono::milliseconds>(t5 - t1).count();

std::cout << ms1 << " " << ms2 << " " << ms3 << " " << ms4 << " loop: " << loop << std::endl;
int key = cv::waitKey(1);
if(key == 'q') {
return 0;
Expand Down
50 changes: 22 additions & 28 deletions include/depthai/pipeline/datatype/CameraControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,10 +105,10 @@ class CameraControl : public Buffer {
void setAutoExposureRegion(uint16_t startX, uint16_t startY, uint16_t width, uint16_t height);

/**
* Set a command to specify auto exposure compenstaion
* @param compensation Compensation value between -128..127
* Set a command to specify auto exposure compensation
* @param compensation Compensation value between -9..9
*/
void setAutoExposureCompensation(int8_t compensation);
void setAutoExposureCompensation(int compensation);

/**
* Set a command to specify auto banding mode
Expand All @@ -119,7 +119,7 @@ class CameraControl : public Buffer {
/**
* Set a command to manually specify exposure
* @param exposureTimeUs Exposure time in microseconds
* @param sensitivityIso Sensitivity as ISO value
* @param sensitivityIso Sensitivity as ISO value, usual range 100..1600
*/
void setManualExposure(uint32_t exposureTimeUs, uint32_t sensitivityIso);

Expand All @@ -138,46 +138,40 @@ class CameraControl : public Buffer {

// Other image controls
/**
* Set a command to specify auto white balance lock
* @param lock Auto white balance lock mode enabled or disabled
*/
void setBrightness(uint16_t value); // TODO move to AE?

/**
* Set a command to specify auto white balance lock
* @param lock Auto white balance lock mode enabled or disabled
* Set a command to adjust image brightness
* @param value Brightness, range -10..10
*/
void setContrast(uint16_t value);
void setBrightness(int value);

/**
* Set a command to specify saturation value
* @param value Saturation
* Set a command to adjust image contrast
* @param value Contrast, range -10..10
*/
void setSaturation(uint16_t value);
void setContrast(int value);

/**
* Set a command to specify sharpness value
* @param value Sharpness
* Set a command to adjust image saturation
* @param value Saturation, range -10..10
*/
void setSharpness(uint16_t value);
void setSaturation(int value);

/**
* Set a command to specify noise reduction strength
* @param value Noise reduction strength
* Set a command to adjust image sharpness
* @param value Sharpness, range 0..4
*/
void setNoiseReductionStrength(uint16_t value);
void setSharpness(int value);

/**
* Set a command to specify luma denoise value
* @param value Luma denoise
* Set a command to adjust luma denoise amount
* @param value Luma denoise amount, range 0..4
*/
void setLumaDenoise(uint16_t value);
void setLumaDenoise(int value);

/**
* Set a command to specify chroma denoise value
* @param value Chroma denoise
* Set a command to adjust chroma denoise amount
* @param value Chroma denoise amount, range 0..4
*/
void setChromaDenoise(uint16_t value);
void setChromaDenoise(int value);

/**
* Set a command to specify scene mode
Expand Down
Loading