Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/develop' into HEAD
Browse files Browse the repository at this point in the history
  • Loading branch information
SzabolcsGergely committed May 15, 2024
2 parents 10e6107 f3f8939 commit 9176486
Show file tree
Hide file tree
Showing 32 changed files with 427 additions and 60 deletions.
6 changes: 4 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 46,7 @@ if(WIN32)
endif()

# Create depthai project
project(depthai VERSION "2.25.0" LANGUAGES CXX C)
project(depthai VERSION "2.25.1" LANGUAGES CXX C)
get_directory_property(has_parent PARENT_DIRECTORY)
if(has_parent)
set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE)
Expand Down Expand Up @@ -219,6 219,7 @@ add_library(${TARGET_CORE_NAME}
src/pipeline/node/DetectionNetwork.cpp
src/pipeline/node/Script.cpp
src/pipeline/node/SpatialDetectionNetwork.cpp
src/pipeline/node/ImageAlign.cpp
src/pipeline/node/SystemLogger.cpp
src/pipeline/node/SpatialLocationCalculator.cpp
src/pipeline/node/AprilTag.cpp
Expand Down Expand Up @@ -251,6 252,7 @@ add_library(${TARGET_CORE_NAME}
src/pipeline/datatype/EdgeDetectorConfig.cpp
src/pipeline/datatype/TrackedFeatures.cpp
src/pipeline/datatype/FeatureTrackerConfig.cpp
src/pipeline/datatype/ImageAlignConfig.cpp
src/pipeline/datatype/ToFConfig.cpp
src/pipeline/datatype/PointCloudConfig.cpp
src/pipeline/datatype/PointCloudData.cpp
Expand Down Expand Up @@ -303,7 305,7 @@ option(DEPTHAI_BUILD_TESTS "Build tests" OFF)
option(DEPTHAI_BUILD_EXAMPLES "Build examples - Requires OpenCV library to be installed" OFF)
option(DEPTHAI_BUILD_DOCS "Build documentation - requires doxygen to be installed" OFF)
option(DEPTHAI_OPENCV_SUPPORT "Enable optional OpenCV support" ON)
option(DEPTHAI_PCL_SUPPORT "Enable optional PCL support" ON)
option(DEPTHAI_PCL_SUPPORT "Enable optional PCL support" OFF)


option(DEPTHAI_BINARIES_RESOURCE_COMPILE "Compile Depthai device side binaries into library" ON)
Expand Down
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -194,6 194,7 @@ The following environment variables can be set to alter default behavior of the
| DEPTHAI_LIBUSB_ANDROID_JAVAVM | JavaVM pointer that is passed to libusb for rootless Android interaction with devices. Interpreted as decimal value of uintptr_t |
| DEPTHAI_CRASHDUMP | Directory in which to save the crash dump. |
| DEPTHAI_CRASHDUMP_TIMEOUT | Specifies the duration in seconds to wait for device reboot when obtaining a crash dump. Crash dump retrieval disabled if 0. |
| DEPTHAI_PCL_SUPPORT | Enables PCL support. |

## Running tests

Expand Down
2 changes: 1 addition & 1 deletion cmake/Depthai/DepthaiBootloaderConfig.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -3,5 3,5 @@ set(DEPTHAI_BOOTLOADER_MATURITY "release")
# set(DEPTHAI_BOOTLOADER_MATURITY "snapshot")

# "version if applicable"
set(DEPTHAI_BOOTLOADER_VERSION "0.0.26")
set(DEPTHAI_BOOTLOADER_VERSION "0.0.27")
# set(DEPTHAI_BOOTLOADER_VERSION "0.0.24 57c26493754e2f00e57f6863b0b1a317f762d5f2")
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 "f134c967666e57000a11ba9dfffc6ddea3c5ef97")
set(DEPTHAI_DEVICE_SIDE_COMMIT "506abdf3f5e901f361801bb8cc155a7b3c214a1e")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
12 changes: 9 additions & 3 deletions cmake/depthaiDependencies.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 22,9 @@ else()
hunter_add_package(Backward)
endif()
hunter_add_package(libnop)
if(DEPTHAI_PCL_SUPPORT)
hunter_add_package(jsoncpp)
endif()
endif()

# If library was build as static, find all dependencies
Expand Down Expand Up @@ -76,13 79,16 @@ endif()

# OpenCV 4 - (optional, quiet always)
find_package(OpenCV 4 QUIET CONFIG)

find_package(jsoncpp QUIET)
if(DEPTHAI_PCL_SUPPORT AND NOT TARGET JsonCpp::JsonCpp)
find_package(jsoncpp)
endif()
set(MODULE_TEMP ${CMAKE_MODULE_PATH})
set(PREFIX_TEMP ${CMAKE_PREFIX_PATH})
set(CMAKE_MODULE_PATH ${_DEPTHAI_MODULE_PATH_ORIGINAL})
set(CMAKE_PREFIX_PATH ${_DEPTHAI_PREFIX_PATH_ORIGINAL})
find_package(PCL QUIET CONFIG COMPONENTS common visualization)
if(DEPTHAI_PCL_SUPPORT)
find_package(PCL CONFIG COMPONENTS common visualization)
endif()
set(CMAKE_MODULE_PATH ${MODULE_TEMP})
set(CMAKE_PREFIX_PATH ${PREFIX_TEMP})

Expand Down
2 changes: 2 additions & 0 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -244,6 244,8 @@ dai_add_example(edge_detector EdgeDetector/edge_detector.cpp ON OFF)
dai_add_example(feature_detector FeatureTracker/feature_detector.cpp ON OFF)
dai_add_example(feature_tracker FeatureTracker/feature_tracker.cpp ON OFF)

# dai_add_example(image_align ImageAlign/rgb_image_align.cpp ON)

# host_side
dai_add_example(device_queue_event host_side/device_queue_event.cpp ON OFF)
dai_add_example(opencv_support host_side/opencv_support.cpp ON OFF)
Expand Down
13 changes: 7 additions & 6 deletions examples/Camera/thermal_cam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,17 22,18 @@ int main() {
// Find the sensor width, height.
int width, height;
bool thermal_found = false;
for (auto &features : d.getConnectedCameraFeatures()) {
if (std::find_if(features.supportedTypes.begin(), features.supportedTypes.end(), [](const dai::CameraSensorType &type) {
return type == dai::CameraSensorType::THERMAL;
}) != features.supportedTypes.end()) {
thermal->setBoardSocket(features.socket); // Thermal will always be on CAM_E
for(auto& features : d.getConnectedCameraFeatures()) {
if(std::find_if(features.supportedTypes.begin(),
features.supportedTypes.end(),
[](const dai::CameraSensorType& type) { return type == dai::CameraSensorType::THERMAL; })
!= features.supportedTypes.end()) {
thermal->setBoardSocket(features.socket); // Thermal will always be on CAM_E
width = features.width;
height = features.height;
thermal_found = true;
}
}
if (!thermal_found) {
if(!thermal_found) {
throw std::runtime_error("Thermal camera not found!");
}
thermal->setPreviewSize(width, height);
Expand Down
143 changes: 143 additions & 0 deletions examples/DepthAlign/rgb_depth_align.cpp
Original file line number Diff line number Diff line change
@@ -0,0 1,143 @@
#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 std::atomic<bool> downscaleColor{true};
static constexpr int fps = 30;
// The disparity is computed at this resolution, then upscaled to RGB resolution
static constexpr auto monoRes = dai::MonoCameraProperties::SensorResolution::THE_720_P;

static float rgbWeight = 0.4f;
static float depthWeight = 0.6f;

static void updateBlendWeights(int percentRgb, void* ctx) {
rgbWeight = float(percentRgb) / 100.f;
depthWeight = 1.f - rgbWeight;
}

int main() {
using namespace std;

// Create pipeline
dai::Pipeline pipeline;
dai::Device device;
std::vector<std::string> queueNames;

// Define sources and outputs
auto camRgb = pipeline.create<dai::node::ColorCamera>();
auto left = pipeline.create<dai::node::MonoCamera>();
auto right = pipeline.create<dai::node::MonoCamera>();
auto stereo = pipeline.create<dai::node::StereoDepth>();

auto depthAlign = pipeline.create<dai::node::DepthAlign>();

auto rgbOut = pipeline.create<dai::node::XLinkOut>();
auto depthOut = pipeline.create<dai::node::XLinkOut>();
auto alignedDepthOut = pipeline.create<dai::node::XLinkOut>();

rgbOut->setStreamName("rgb");
queueNames.push_back("rgb");
depthOut->setStreamName("depth");
queueNames.push_back("depth");
alignedDepthOut->setStreamName("depth_aligned");
queueNames.push_back("depth_aligned");

// Properties
camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A);
camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P);
camRgb->setFps(fps);
camRgb->setIspScale(2, 3);
// For now, RGB needs fixed focus to properly align with depth.
// This value was used during calibration
try {
auto calibData = device.readCalibration2();
auto lensPosition = calibData.getLensPosition(dai::CameraBoardSocket::CAM_A);
if(lensPosition) {
camRgb->initialControl.setManualFocus(lensPosition);
}
} catch(const std::exception& ex) {
std::cout << ex.what() << std::endl;
return 1;
}

left->setResolution(monoRes);
left->setCamera("left");
left->setFps(fps);
right->setResolution(monoRes);
right->setCamera("right");
right->setFps(fps);

stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);

// Linking
camRgb->isp.link(rgbOut->input);
left->out.link(stereo->left);
right->out.link(stereo->right);
stereo->depth.link(depthAlign->inputDepth);

depthAlign->outputDepthAlign.link(alignedDepthOut->input);
depthAlign->properties.alignTo = dai::CameraBoardSocket::CAM_A;
stereo->depth.link(depthOut->input);

// Connect to device and start pipeline
device.startPipeline(pipeline);

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

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

auto rgbWindowName = "rgb";
auto depthWindowName = "depth";
auto blendedWindowName = "rgb-depth";
auto alignedDepth = "depth_aligned";
cv::namedWindow(rgbWindowName);
cv::namedWindow(depthWindowName);
cv::namedWindow(blendedWindowName);
cv::namedWindow(alignedDepth);
int defaultValue = (int)(rgbWeight * 100);
cv::createTrackbar("RGB Weight %", blendedWindowName, &defaultValue, 100, updateBlendWeights);

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

auto queueEvents = device.getQueueEvents(queueNames);
for(const auto& name : queueEvents) {
auto packets = device.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 == depthWindowName) {
frame[name] = latestPacket[name]->getFrame();
} else if (name == rgbWindowName) {
frame[name] = latestPacket[name]->getCvFrame();
}
else {
frame[name] = latestPacket[name]->getFrame();
}


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

int key = cv::waitKey(1);
if(key == 'q' || key == 'Q') {
return 0;
}
}
return 0;
}
2 changes: 1 addition & 1 deletion examples/FeatureTracker/feature_tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 16,7 @@ class FeatureTrackerDrawer {
// for how many frames the feature is tracked
static int trackedFeaturesPathLength;

using featureIdType = decltype(dai::Point2f::x);
using featureIdType = decltype(dai::TrackedFeature::id);

std::unordered_set<featureIdType> trackedIDs;
std::unordered_map<featureIdType, std::deque<dai::Point2f>> trackedFeaturesPath;
Expand Down
2 changes: 1 addition & 1 deletion examples/IMU/imu_firmware_update.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 36,7 @@ int main() {

while(true) {
bool fwUpdateFinished;
float percentage;
unsigned int percentage;
std::tie(fwUpdateFinished, percentage) = device.getIMUFirmwareUpdateStatus();
std::cout << "IMU FW update status: " << std::setprecision(1) << percentage << std::endl;
if(fwUpdateFinished) {
Expand Down
3 changes: 1 addition & 2 deletions include/depthai/common/CameraFeatures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 49,7 @@ inline std::ostream& operator<<(std::ostream& out, const dai::CameraSensorConfig
out << "minFps: " << config.minFps << ", ";
out << "maxFps: " << config.maxFps << ", ";
out << "type: " << config.type << ", ";
out << "fov: "
<< "{x:" << config.fov.x << ", ";
out << "fov: " << "{x:" << config.fov.x << ", ";
out << "y: " << config.fov.y << ", ";
out << "width: " << config.fov.width << ", ";
out << "height: " << config.fov.height << "}";
Expand Down
2 changes: 1 addition & 1 deletion include/depthai/device/Device.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 132,7 @@ class Device : public DeviceBase {
/**
* Gets an input queue corresponding to stream name. If it doesn't exist it throws. Also sets queue options
*
* @param name Queue/stream name, set in XLinkOut node
* @param name Queue/stream name, set in XLinkIn node
* @param maxSize Maximum number of messages in queue
* @param blocking Queue behavior once full. True: blocking, false: overwriting of oldest messages. Default: true
* @returns Smart pointer to DataInputQueue
Expand Down
2 changes: 1 addition & 1 deletion include/depthai/device/DeviceBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -673,7 673,7 @@ class DeviceBase {
* return value true and 100 means that the update was successful
* return value true and other than 100 means that the update failed
*/
std::tuple<bool, float> getIMUFirmwareUpdateStatus();
std::tuple<bool, unsigned int> getIMUFirmwareUpdateStatus();

/**
* Retrieves current DDR memory information from device
Expand Down
9 changes: 8 additions & 1 deletion include/depthai/device/DeviceBootloader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -441,6 441,12 @@ class DeviceBootloader {
*/
Version getVersion() const;

/**
* @return Version of the bootloader that is flashed on the device.
* Nullopt when the version could not be retrieved because the device was in X_LINK_UNBOOTED state before booting the bootloader.
*/
tl::optional<Version> getFlashedVersion() const;

/**
* @returns True when bootloader was booted using latest bootloader integrated in the library.
* False when bootloader is already running on the device and just connected to.
Expand Down Expand Up @@ -504,6 510,7 @@ class DeviceBootloader {

bool isEmbedded = false;
Type bootloaderType;
tl::optional<Version> flashedVersion;

// closed
std::atomic<bool> closed{false};
Expand Down Expand Up @@ -586,4 593,4 @@ inline std::ostream& operator<<(std::ostream& out, const dai::DeviceBootloader::

inline std::ostream& operator<<(std::ostream& out, const dai::DeviceBootloader::Version& v) {
return out << v.toString();
}
}
36 changes: 36 additions & 0 deletions include/depthai/pipeline/datatype/ImageAlignConfig.hpp
Original file line number Diff line number Diff line change
@@ -0,0 1,36 @@
#pragma once

#include <unordered_map>
#include <vector>

#include "depthai-shared/datatype/RawImageAlignConfig.hpp"
#include "depthai/pipeline/datatype/Buffer.hpp"

namespace dai {

/**
* ImageAlignConfig message
*/
class ImageAlignConfig : public Buffer {
std::shared_ptr<RawBuffer> serialize() const override;
RawImageAlignConfig& cfg;

public:
ImageAlignConfig();
explicit ImageAlignConfig(std::shared_ptr<RawImageAlignConfig> ptr);
virtual ~ImageAlignConfig() = default;

/**
* Set explicit configuration.
* @param config Explicit configuration
*/
ImageAlignConfig& set(dai::RawImageAlignConfig config);

/**
* Retrieve configuration data for SpatialLocationCalculator.
* @returns config for SpatialLocationCalculator
*/
dai::RawImageAlignConfig get() const;
};

} // namespace dai
7 changes: 0 additions & 7 deletions include/depthai/pipeline/datatype/ToFConfig.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,20 16,13 @@ class ToFConfig : public Buffer {
RawToFConfig& cfg;

public:
// Raw* mirror
using DepthParams = RawToFConfig::DepthParams;

/**
* Construct ToFConfig message.
*/
ToFConfig();
explicit ToFConfig(std::shared_ptr<RawToFConfig> ptr);
virtual ~ToFConfig() = default;

ToFConfig& setDepthParams(dai::ToFConfig::DepthParams config);
ToFConfig& setFreqModUsed(dai::ToFConfig::DepthParams::TypeFMod fmod);
ToFConfig& setAvgPhaseShuffle(bool enable);
ToFConfig& setMinAmplitude(float minamp);
/**
* @param median Set kernel size for median filtering, or disable
*/
Expand Down
Loading

0 comments on commit 9176486

Please sign in to comment.