Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/release_v2.23.0' into main
Browse files Browse the repository at this point in the history
  • Loading branch information
themarpe committed Oct 3, 2023
2 parents 82ab07d + f1b6d30 commit bcd7a0e
Show file tree
Hide file tree
Showing 55 changed files with 709 additions and 463 deletions.
16 changes: 12 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,9 @@ if(NOT WIN32)
set(HUNTER_CONFIGURATION_TYPES "Release" CACHE STRING "Hunter dependencies list of build configurations")
endif()

# Early options
option(DEPTHAI_ENABLE_LIBUSB "Enable usage of libusb and interaction with USB devices" ON)

# Set type to canonicalize relative paths for user-provided toolchain
set(CMAKE_TOOLCHAIN_FILE "" CACHE FILEPATH "CMake toolchain path")

Expand Down Expand Up @@ -43,7 +46,7 @@ if(WIN32)
endif()

# Create depthai project
project(depthai VERSION "2.22.0" LANGUAGES CXX C)
project(depthai VERSION "2.23.0" LANGUAGES CXX C)
get_directory_property(has_parent PARENT_DIRECTORY)
if(has_parent)
set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE)
Expand Down Expand Up @@ -251,6 +254,7 @@ add_library(${TARGET_CORE_NAME}
src/utility/Environment.cpp
src/utility/XLinkGlobalProfilingLogger.cpp
src/utility/Logging.cpp
src/utility/EepromDataParser.cpp
src/xlink/XLinkConnection.cpp
src/xlink/XLinkStream.cpp
src/openvino/OpenVINO.cpp
Expand Down Expand Up @@ -446,13 +450,16 @@ target_link_libraries(${TARGET_CORE_NAME}
set(DEPTHAI_DEVICE_VERSION "${DEPTHAI_DEVICE_SIDE_COMMIT}")
target_compile_definitions(${TARGET_CORE_NAME}
PRIVATE
# XLink required define
__PC__
# Add depthai-device version
DEPTHAI_DEVICE_VERSION="${DEPTHAI_DEVICE_VERSION}"
# Add depthai-bootloader version
DEPTHAI_BOOTLOADER_VERSION="${DEPTHAI_BOOTLOADER_VERSION}"
)
# Add compile flag if libusb is available
if(DEPTHAI_ENABLE_LIBUSB)
target_compile_definitions(${TARGET_CORE_NAME} PRIVATE DEPTHAI_ENABLE_LIBUSB)
set(DEPTHAI_HAVE_LIBUSB_SUPPORT ON)
endif()

# Add Backward dependency if enabled (On by default)
if(DEPTHAI_ENABLE_BACKWARD)
Expand Down Expand Up @@ -481,8 +488,9 @@ macro(add_runtime_dependencies depending_target dependency)
set(required_dll_files ${dlls} ${depthai_dll_libraries})
# Copy the required dlls
add_custom_command(TARGET ${depending_target} POST_BUILD COMMAND
${CMAKE_COMMAND} -E copy_if_different ${required_dll_files} $<TARGET_FILE_DIR:${depending_target}>
"$<$<BOOL:${required_dll_files}>:${CMAKE_COMMAND};-E;copy_if_different;${required_dll_files};$<TARGET_FILE_DIR:${depending_target}>>"
COMMAND_EXPAND_LISTS
VERBATIM
)
message(STATUS "Required dlls for core are: ${required_dll_files}")
endif()
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 "f033fd9c7eb0b3578d12f90302e87759c78cfb36")
set(DEPTHAI_DEVICE_SIDE_COMMIT "39a9d271a9ed0172f6481877723fca96d41b54c6")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
6 changes: 4 additions & 2 deletions cmake/Hunter/config.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,10 @@ hunter_config(
hunter_config(
XLink
VERSION "luxonis-2021.4.2-develop"
URL "https://github.com/luxonis/XLink/archive/457b23fb33e1146610e1a4e52defa7565046977a.tar.gz"
SHA1 "006a2bd391498aea7895e988b787a420e7f51fa9"
URL "https://github.com/luxonis/XLink/archive/c940feaf9321f06a7d9660f28e686a9718135f38.tar.gz"
SHA1 "52935b6ceb470ee632de3348b9d2aaa2c6c24ac0"
CMAKE_ARGS
XLINK_ENABLE_LIBUSB=${DEPTHAI_ENABLE_LIBUSB}
)

hunter_config(
Expand Down
23 changes: 23 additions & 0 deletions cmake/config.hpp.in
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,32 @@
// This build supports OpenCV integration?
#cmakedefine DEPTHAI_HAVE_OPENCV_SUPPORT

// This build supports libusb?
#cmakedefine DEPTHAI_HAVE_LIBUSB_SUPPORT

// Build specific settings overwrite
#ifdef DEPTHAI_TARGET_CORE
#ifndef DEPTHAI_TARGET_OPENCV
#undef DEPTHAI_HAVE_OPENCV_SUPPORT
#endif
#endif

namespace dai
{
namespace build
{

#ifdef DEPTHAI_HAVE_OPENCV_SUPPORT
constexpr static bool HAVE_OPENCV_SUPPORT = true;
#else
constexpr static bool HAVE_OPENCV_SUPPORT = false;
#endif

#ifdef DEPTHAI_HAVE_LIBUSB_SUPPORT
constexpr static bool HAVE_LIBUSB_SUPPORT = true;
#else
constexpr static bool HAVE_LIBUSB_SUPPORT = false;
#endif

} // namespace build
} // namespace dai
4 changes: 3 additions & 1 deletion examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -83,8 +83,9 @@ function(dai_add_example example_name example_src enable_test)
set(depthai_dll_libraries "$<TARGET_RUNTIME_DLLS:${example_name}>")
endif()
add_custom_command(TARGET ${example_name} POST_BUILD COMMAND
${CMAKE_COMMAND} -E copy_if_different ${depthai_dll_libraries} $<TARGET_FILE_DIR:${example_name}>
"$<$<BOOL:${depthai_dll_libraries}>:${CMAKE_COMMAND};-E;copy_if_different;${depthai_dll_libraries};$<TARGET_FILE_DIR:${example_name}>>"
COMMAND_EXPAND_LISTS
VERBATIM
)
endif()
endfunction()
Expand Down Expand Up @@ -320,6 +321,7 @@ dai_add_example(script_json_communication Script/script_json_communication.cpp O
dai_add_example(script_change_pipeline_flow Script/script_change_pipeline_flow.cpp OFF)
target_compile_definitions(script_change_pipeline_flow PRIVATE BLOB_PATH="${mobilenet_5shaves_blob}")
dai_add_example(script_get_device_info Script/script_get_device_info.cpp ON)
dai_add_example(script_read_calibration Script/script_read_calibration.cpp ON)

# SpatialDetection
dai_add_example(spatial_location_calculator SpatialDetection/spatial_location_calculator.cpp ON)
Expand Down
2 changes: 1 addition & 1 deletion examples/ColorCamera/rgb_preview.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ int main() {
}

// Device name
cout << "Device name: " << device.getDeviceName() << endl;
cout << "Device name: " << device.getDeviceName() << " Product name: " << device.getProductName() << endl;

// Output queue will be used to get the rgb frames from the output defined above
auto qRgb = device.getOutputQueue("rgb", 4, false);
Expand Down
43 changes: 43 additions & 0 deletions examples/Script/script_read_calibration.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
#include <iostream>

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

int main() {
using namespace std;

// Start defining a pipeline
dai::Pipeline pipeline;

// Script node
auto script = pipeline.create<dai::node::Script>();
script->setProcessor(dai::ProcessorType::LEON_CSS);
script->setScript(R"(
import time
cal = Device.readCalibration2()
left_camera_id = cal.getStereoLeftCameraId()
right_camera_id = cal.getStereoRightCameraId()
extrinsics = cal.getCameraExtrinsics(left_camera_id, right_camera_id)
intrinsics_left = cal.getCameraIntrinsics(left_camera_id)
node.info(extrinsics.__str__())
node.info(intrinsics_left.__str__())
time.sleep(1)
node.io['end'].send(Buffer(32))
)");

auto xout = pipeline.create<dai::node::XLinkOut>();
xout->setStreamName("end");

script->outputs["end"].link(xout->input);

// Connect to device with pipeline
dai::Device device(pipeline);

device.getOutputQueue("end")->get();

return 0;
}
4 changes: 2 additions & 2 deletions examples/Warp/warp_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ int main() {
constexpr std::tuple<int, int> WARP1_OUTPUT_FRAME_SIZE = {992, 500};
warp1->setOutputSize(WARP1_OUTPUT_FRAME_SIZE);
warp1->setMaxOutputFrameSize(std::get<0>(WARP1_OUTPUT_FRAME_SIZE) * std::get<1>(WARP1_OUTPUT_FRAME_SIZE) * 3);
warp1->setInterpolation(dai::node::Warp::Properties::Interpolation::BYPASS);
warp1->setInterpolation(dai::Interpolation::NEAREST_NEIGHBOR);
warp1->setHwIds({1});

camRgb->preview.link(warp1->inputImage);
Expand All @@ -47,7 +47,7 @@ int main() {
// clang-format on
warp2->setWarpMesh(mesh2, 3, 3);
warp2->setMaxOutputFrameSize(maxFrameSize);
warp2->setInterpolation(dai::node::Warp::Properties::Interpolation::BICUBIC);
warp2->setInterpolation(dai::Interpolation::BICUBIC);
warp2->setHwIds({2});

camRgb->preview.link(warp2->inputImage);
Expand Down
1 change: 1 addition & 0 deletions include/depthai/common/CameraFeatures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ inline std::ostream& operator<<(std::ostream& out, const dai::CameraFeatures& ca
}
out << "], ";
out << "hasAutofocus: " << camera.hasAutofocus << ", ";
out << "hasAutofocusIC: " << camera.hasAutofocusIC << ", ";
out << "name: " << camera.name << "}";

return out;
Expand Down
31 changes: 31 additions & 0 deletions include/depthai/device/CalibrationHandler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -353,6 +353,37 @@ class CalibrationHandler {
uint32_t boardOptions,
std::string boardCustom = "");

/**
* Set the Board Info object. Creates version 7 EEPROM data
*
* @param deviceName Sets device name.
* @param productName Sets product name (alias).
* @param boardName Sets board name.
* @param boardRev Sets board revision id.
* @param boardConf Sets board configuration id.
* @param hardwareConf Sets hardware configuration id.
* @param batchName Sets batch name. Not supported anymore
* @param batchTime Sets batch time (unix timestamp).
* @param boardCustom Sets a custom board (Default empty string).
*/
void setBoardInfo(std::string deviceName,
std::string productName,
std::string boardName,
std::string boardRev,
std::string boardConf,
std::string hardwareConf,
std::string batchName,
uint64_t batchTime,
uint32_t boardOptions,
std::string boardCustom = "");

/**
* Set the deviceName which responses to getDeviceName of Device
*
* @param deviceName Sets device name.
*/
void setDeviceName(std::string deviceName);

/**
* Set the productName which acts as alisas for users to identify the device
*
Expand Down
15 changes: 9 additions & 6 deletions include/depthai/device/DeviceBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,8 +292,8 @@ class DeviceBase {

/**
* Connects to device 'devInfo' with custom config.
* @param devInfo DeviceInfo which specifies which device to connect to
* @param config Device custom configuration to boot with
* @param devInfo DeviceInfo which specifies which device to connect to
*/
DeviceBase(Config config, const DeviceInfo& devInfo);

Expand Down Expand Up @@ -364,8 +364,8 @@ class DeviceBase {

/**
* Connects to device specified by devInfo.
* @param version OpenVINO version which the device will be booted with
* @param config Config with which specifies which device to connect to
* @param config Config with which the device will be booted with
* @param devInfo DeviceInfo which specifies which device to connect to
* @param maxUsbSpeed Maximum allowed USB speed
*/
DeviceBase(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed);
Expand Down Expand Up @@ -456,6 +456,12 @@ class DeviceBase {
*/
std::string getDeviceName();

/**
* Get product name if available
* @returns product name or empty string if not available
*/
std::string getProductName();

/**
* Get MxId of device
*
Expand Down Expand Up @@ -867,7 +873,6 @@ class DeviceBase {
void init(OpenVINO::Version version);
void init(OpenVINO::Version version, const dai::Path& pathToCmd);
void init(OpenVINO::Version version, UsbSpeed maxUsbSpeed);
void init(OpenVINO::Version version, bool usb2Mode, const dai::Path& pathToMvcmd);
void init(OpenVINO::Version version, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd);
void init(const Pipeline& pipeline);
void init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed);
Expand All @@ -876,9 +881,7 @@ class DeviceBase {
void init(const Pipeline& pipeline, const DeviceInfo& devInfo, bool usb2Mode);
void init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed);
void init(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd);
void init(const Pipeline& pipeline, bool usb2Mode, const dai::Path& pathToMvcmd);
void init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd);
void init(Config config, bool usb2Mode, const dai::Path& pathToMvcmd);
void init(Config config, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd);
void init(Config config, UsbSpeed maxUsbSpeed);
void init(Config config, const dai::Path& pathToCmd);
Expand Down
16 changes: 0 additions & 16 deletions include/depthai/pipeline/datatype/AprilTags.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,22 +25,6 @@ class AprilTags : public Buffer {

std::vector<AprilTag>& aprilTags;

/**
* Retrieves image timestamp related to dai::Clock::now()
*/
std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> getTimestamp() const;

/**
* Retrieves image timestamp directly captured from device's monotonic clock,
* not synchronized to host time. Used mostly for debugging
*/
std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> getTimestampDevice() const;

/**
* Retrieves image sequence number
*/
int64_t getSequenceNum() const;

/**
* Sets image timestamp related to dai::Clock::now()
*/
Expand Down
32 changes: 32 additions & 0 deletions include/depthai/pipeline/datatype/Buffer.hpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#pragma once

#include <chrono>
#include <unordered_map>
#include <vector>

Expand Down Expand Up @@ -34,6 +35,37 @@ class Buffer : public ADatatype {
* @param data Moves data to internal buffer
*/
void setData(std::vector<std::uint8_t>&& data);

/**
* Retrieves timestamp related to dai::Clock::now()
*/
std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> getTimestamp() const;

/**
* Retrieves timestamp directly captured from device's monotonic clock,
* not synchronized to host time. Used mostly for debugging
*/
std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> getTimestampDevice() const;

/**
* Retrieves sequence number
*/
int64_t getSequenceNum() const;

/**
* Sets timestamp related to dai::Clock::now()
*/
Buffer& setTimestamp(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> timestamp);

/**
* Sets timestamp related to dai::Clock::now()
*/
Buffer& setTimestampDevice(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> timestamp);

/**
* Retrieves sequence number
*/
Buffer& setSequenceNum(int64_t sequenceNum);
};

} // namespace dai
9 changes: 9 additions & 0 deletions include/depthai/pipeline/datatype/ImageManipConfig.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,6 +187,12 @@ class ImageManipConfig : public Buffer {
*/
ImageManipConfig& setKeepAspectRatio(bool keep);

/**
* Specify which interpolation method to use
* @param interpolation type of interpolation
*/
ImageManipConfig& setInterpolation(dai::Interpolation interpolation);

// Functions to retrieve properties
/**
* @returns Top left X coordinate of crop region
Expand Down Expand Up @@ -254,6 +260,9 @@ class ImageManipConfig : public Buffer {
* @returns config for ImageManip
*/
dai::RawImageManipConfig get() const;

/// Retrieve which interpolation method to use
dai::Interpolation getInterpolation() const;
};

} // namespace dai
Loading

0 comments on commit bcd7a0e

Please sign in to comment.