diff --git a/depthai-ros/CHANGELOG.rst b/depthai-ros/CHANGELOG.rst index 6e6b6c74..6edfe81d 100644 --- a/depthai-ros/CHANGELOG.rst +++ b/depthai-ros/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package depthai-ros ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.10.5 (2025-01-09) +------------------- +* Fix low bandwidth issues +* New stereo filters +* Diagnostics update +* Fix IR calculation 2.10.4 (2024-11-07) ------------------- diff --git a/depthai-ros/CMakeLists.txt b/depthai-ros/CMakeLists.txt index 1096cb9d..7c913b18 100644 --- a/depthai-ros/CMakeLists.txt +++ b/depthai-ros/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.10.2) # CMake version in Ubuntu 18.04 LTS -project(depthai-ros VERSION 2.10.4 LANGUAGES CXX C) +project(depthai-ros VERSION 2.10.5 LANGUAGES CXX C) set(CMAKE_CXX_STANDARD 14) diff --git a/depthai-ros/package.xml b/depthai-ros/package.xml index ed584774..4fcf6ffb 100644 --- a/depthai-ros/package.xml +++ b/depthai-ros/package.xml @@ -1,7 +1,7 @@ depthai-ros - 2.10.4 + 2.10.5 The depthai-ros package diff --git a/depthai_bridge/CMakeLists.txt b/depthai_bridge/CMakeLists.txt index 7411e478..2b577df7 100644 --- a/depthai_bridge/CMakeLists.txt +++ b/depthai_bridge/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.10.2) # CMake version in Ubuntu 18.04 LTS set(CMAKE_POSITION_INDEPENDENT_CODE ON) -project(depthai_bridge VERSION 2.10.4 LANGUAGES CXX C) +project(depthai_bridge VERSION 2.10.5 LANGUAGES CXX C) set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) @@ -28,6 +28,7 @@ message(STATUS "------------------------------------------") set(BUILD_TOOL_INCLUDE_DIRS ${ament_INCLUDE_DIRS}) +find_package(ament_index_cpp REQUIRED) find_package(camera_info_manager REQUIRED) find_package(cv_bridge REQUIRED) find_package(depthai_ros_msgs REQUIRED) @@ -45,6 +46,7 @@ find_package(composition_interfaces REQUIRED) find_package(ffmpeg_image_transport_msgs REQUIRED) set(dependencies + ament_index_cpp camera_info_manager cv_bridge depthai_ros_msgs diff --git a/depthai_bridge/package.xml b/depthai_bridge/package.xml index fd41081e..13bab0c1 100644 --- a/depthai_bridge/package.xml +++ b/depthai_bridge/package.xml @@ -1,7 +1,7 @@ depthai_bridge - 2.10.4 + 2.10.5 The depthai_bridge package Adam Serafin diff --git a/depthai_bridge/src/TFPublisher.cpp b/depthai_bridge/src/TFPublisher.cpp index 8e52744e..3bc1f470 100644 --- a/depthai_bridge/src/TFPublisher.cpp +++ b/depthai_bridge/src/TFPublisher.cpp @@ -242,7 +242,7 @@ std::string TFPublisher::getURDF() { RCLCPP_DEBUG(logger, "Xacro command: %s", cmd.c_str()); std::array buffer; std::string result; - std::unique_ptr pipe(popen(cmd.c_str(), "r"), pclose); + std::unique_ptr pipe(popen(cmd.c_str(), "r"), pclose); if(!pipe) { throw std::runtime_error("popen() failed!"); } diff --git a/depthai_descriptions/CMakeLists.txt b/depthai_descriptions/CMakeLists.txt index 29f1be7e..bc03ec82 100644 --- a/depthai_descriptions/CMakeLists.txt +++ b/depthai_descriptions/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(depthai_descriptions VERSION 2.10.4) +project(depthai_descriptions VERSION 2.10.5) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) diff --git a/depthai_descriptions/package.xml b/depthai_descriptions/package.xml index c17db101..7128de43 100644 --- a/depthai_descriptions/package.xml +++ b/depthai_descriptions/package.xml @@ -1,7 +1,7 @@ depthai_descriptions - 2.10.4 + 2.10.5 The depthai_descriptions package Adam Serafin diff --git a/depthai_examples/CMakeLists.txt b/depthai_examples/CMakeLists.txt index c41cab19..d4655d93 100644 --- a/depthai_examples/CMakeLists.txt +++ b/depthai_examples/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) # CMake version in Ubuntu 18.04 LTS -project(depthai_examples VERSION 2.10.4 LANGUAGES CXX C) +project(depthai_examples VERSION 2.10.5 LANGUAGES CXX C) set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) diff --git a/depthai_examples/package.xml b/depthai_examples/package.xml index 19e99d39..8d3bf94e 100644 --- a/depthai_examples/package.xml +++ b/depthai_examples/package.xml @@ -1,7 +1,7 @@ depthai_examples - 2.10.4 + 2.10.5 The depthai_examples package diff --git a/depthai_filters/CMakeLists.txt b/depthai_filters/CMakeLists.txt index 40f1d368..e70aa597 100644 --- a/depthai_filters/CMakeLists.txt +++ b/depthai_filters/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(depthai_filters VERSION 2.10.4 LANGUAGES CXX C) +project(depthai_filters VERSION 2.10.5 LANGUAGES CXX C) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) diff --git a/depthai_filters/package.xml b/depthai_filters/package.xml index 8c2389d7..418d56be 100644 --- a/depthai_filters/package.xml +++ b/depthai_filters/package.xml @@ -2,7 +2,7 @@ depthai_filters - 2.10.4 + 2.10.5 Depthai filters package Adam Serafin MIT diff --git a/depthai_filters/src/detection2d_overlay.cpp b/depthai_filters/src/detection2d_overlay.cpp index 7e17e4b9..a682f429 100644 --- a/depthai_filters/src/detection2d_overlay.cpp +++ b/depthai_filters/src/detection2d_overlay.cpp @@ -13,8 +13,8 @@ Detection2DOverlay::Detection2DOverlay(const rclcpp::NodeOptions& options) : rcl void Detection2DOverlay::onInit() { previewSub.subscribe(this, "rgb/preview/image_raw"); detSub.subscribe(this, "nn/detections"); - sync = std::make_unique>(syncPolicy(10), previewSub, detSub); - sync->registerCallback(std::bind(&Detection2DOverlay::overlayCB, this, std::placeholders::_1, std::placeholders::_2 )); + sync = std::make_unique>(syncPolicy(10), previewSub, detSub); + sync->registerCallback(std::bind(&Detection2DOverlay::overlayCB, this, std::placeholders::_1, std::placeholders::_2)); overlayPub = this->create_publisher("overlay", 10); labelMap = this->declare_parameter>("label_map", labelMap); } diff --git a/depthai_ros_driver/CMakeLists.txt b/depthai_ros_driver/CMakeLists.txt index 4d692ec4..7731edff 100644 --- a/depthai_ros_driver/CMakeLists.txt +++ b/depthai_ros_driver/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.22) -project(depthai_ros_driver VERSION 2.10.4) +project(depthai_ros_driver VERSION 2.10.5) set(CMAKE_POSITION_INDEPENDENT_CODE ON) set(CMAKE_BUILD_SHARED_LIBS ON) set(CMAKE_EXPORT_COMPILE_COMMANDS ON) diff --git a/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/nn/spatial_detection.hpp b/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/nn/spatial_detection.hpp index 478e4178..ebff5159 100644 --- a/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/nn/spatial_detection.hpp +++ b/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/nn/spatial_detection.hpp @@ -77,7 +77,7 @@ class SpatialDetection : public BaseNode { pubConf.height = height; pubConf.daiNodeName = getName(); pubConf.topicName = "~/" + getName() + "/passthrough"; - pubConf.infoSuffix = "/passthrough"; + pubConf.infoSuffix = "/passthrough"; pubConf.socket = static_cast(ph->getParam("i_board_socket_id")); ptPub->setup(device, convConf, pubConf); @@ -98,7 +98,7 @@ class SpatialDetection : public BaseNode { pubConf.height = ph->getOtherNodeParam(sensor_helpers::getNodeName(getROSNode(), sensor_helpers::NodeNameEnum::Stereo), "i_height"); pubConf.daiNodeName = getName(); pubConf.topicName = "~/" + getName() + "/passthrough_depth"; - pubConf.infoSuffix = "/passthrough_depth"; + pubConf.infoSuffix = "/passthrough_depth"; pubConf.socket = socket; ptDepthPub->setup(device, convConf, pubConf); diff --git a/depthai_ros_driver/include/depthai_ros_driver/param_handlers/nn_param_handler.hpp b/depthai_ros_driver/include/depthai_ros_driver/param_handlers/nn_param_handler.hpp index 9e287363..f16c8d46 100644 --- a/depthai_ros_driver/include/depthai_ros_driver/param_handlers/nn_param_handler.hpp +++ b/depthai_ros_driver/include/depthai_ros_driver/param_handlers/nn_param_handler.hpp @@ -40,7 +40,7 @@ class NNParamHandler : public BaseParamHandler { template void declareParams(std::shared_ptr nn, std::shared_ptr imageManip) { declareAndLogParam("i_disable_resize", false); - declareAndLogParam("i_desqueeze_output", false); + declareAndLogParam("i_desqueeze_output", false); declareAndLogParam("i_enable_passthrough", false); declareAndLogParam("i_enable_passthrough_depth", false); declareAndLogParam("i_get_base_device_timestamp", false); diff --git a/depthai_ros_driver/include/depthai_ros_driver/utils.hpp b/depthai_ros_driver/include/depthai_ros_driver/utils.hpp index 28edf7cf..168e94c6 100644 --- a/depthai_ros_driver/include/depthai_ros_driver/utils.hpp +++ b/depthai_ros_driver/include/depthai_ros_driver/utils.hpp @@ -47,6 +47,7 @@ struct ImgConverterConfig { bool getBaseDeviceTimestamp = false; bool updateROSBaseTimeOnRosMsg = false; bool lowBandwidth = false; + bool isStereo = false; dai::RawImgFrame::Type encoding = dai::RawImgFrame::Type::BGR888i; bool addExposureOffset = false; dai::CameraExposureOffset expOffset = dai::CameraExposureOffset::START; @@ -66,7 +67,7 @@ struct ImgPublisherConfig { dai::CameraBoardSocket rightSocket = dai::CameraBoardSocket::CAM_C; std::string calibrationFile = ""; std::string topicSuffix = "/image_raw"; - std::string infoSuffix = ""; + std::string infoSuffix = ""; std::string compressedTopicSuffix = "/image_raw/compressed"; std::string infoMgrSuffix = ""; bool rectified = false; diff --git a/depthai_ros_driver/package.xml b/depthai_ros_driver/package.xml index 05f96186..372b0b56 100644 --- a/depthai_ros_driver/package.xml +++ b/depthai_ros_driver/package.xml @@ -2,7 +2,7 @@ depthai_ros_driver - 2.10.4 + 2.10.5 Depthai ROS Monolithic node. Adam Serafin diff --git a/depthai_ros_driver/src/dai_nodes/sensors/img_pub.cpp b/depthai_ros_driver/src/dai_nodes/sensors/img_pub.cpp index 20583f5e..0e8220c4 100644 --- a/depthai_ros_driver/src/dai_nodes/sensors/img_pub.cpp +++ b/depthai_ros_driver/src/dai_nodes/sensors/img_pub.cpp @@ -69,10 +69,12 @@ void ImagePublisher::setup(std::shared_ptr device, const utils::Img ffmpegPub = node->create_publisher( pubConfig.topicName + pubConfig.compressedTopicSuffix, rclcpp::QoS(10), pubOptions); } - infoPub = node->create_publisher(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions); + infoPub = + node->create_publisher(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions); } else if(ipcEnabled) { imgPub = node->create_publisher(pubConfig.topicName + pubConfig.topicSuffix, rclcpp::QoS(10), pubOptions); - infoPub = node->create_publisher(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions); + infoPub = + node->create_publisher(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions); } else { imgPubIT = image_transport::create_camera_publisher(node.get(), pubConfig.topicName + pubConfig.topicSuffix); } @@ -97,7 +99,7 @@ void ImagePublisher::createImageConverter(std::shared_ptr device) { if(convConfig.alphaScalingEnabled) { converter->setAlphaScaling(convConfig.alphaScaling); } - if(!convConfig.outputDisparity) { + if(convConfig.isStereo && !convConfig.outputDisparity) { auto calHandler = device->readCalibration(); double baseline = calHandler.getBaselineDistance(pubConfig.leftSocket, pubConfig.rightSocket, false); if(convConfig.reverseSocketOrder) { @@ -113,8 +115,10 @@ std::shared_ptr ImagePublisher::createEncoder(std::shar auto enc = pipeline->create(); enc->setQuality(encoderConfig.quality); enc->setProfile(encoderConfig.profile); - enc->setBitrate(encoderConfig.bitrate); - enc->setKeyframeFrequency(encoderConfig.frameFreq); + if(encoderConfig.profile != dai::VideoEncoderProperties::Profile::MJPEG) { + enc->setBitrate(encoderConfig.bitrate); + enc->setKeyframeFrequency(encoderConfig.frameFreq); + } return enc; } void ImagePublisher::createInfoManager(std::shared_ptr device) { diff --git a/depthai_ros_driver/src/dai_nodes/sensors/stereo.cpp b/depthai_ros_driver/src/dai_nodes/sensors/stereo.cpp index a53e8cae..66848add 100644 --- a/depthai_ros_driver/src/dai_nodes/sensors/stereo.cpp +++ b/depthai_ros_driver/src/dai_nodes/sensors/stereo.cpp @@ -194,11 +194,12 @@ void Stereo::setupStereoQueue(std::shared_ptr device) { convConfig.alphaScaling = ph->getParam("i_alpha_scaling"); } convConfig.outputDisparity = ph->getParam("i_output_disparity"); + convConfig.isStereo = true; utils::ImgPublisherConfig pubConf; pubConf.daiNodeName = getName(); pubConf.topicName = "~/" + getName(); - pubConf.topicSuffix = rsCompabilityMode() ? "/image_rect_raw" : "/image_raw"; + pubConf.topicSuffix = rsCompabilityMode() ? "/image_rect_raw" : "/image_raw"; pubConf.rectified = !convConfig.alphaScalingEnabled; pubConf.width = ph->getParam("i_width"); pubConf.height = ph->getParam("i_height"); diff --git a/depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp b/depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp index 2650a593..24744099 100644 --- a/depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp +++ b/depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp @@ -79,19 +79,19 @@ void SensorParamHandler::declareParams(std::shared_ptr mo } monoCam->setImageOrientation( utils::getValFromMap(declareAndLogParam("i_sensor_img_orientation", "AUTO"), dai_nodes::sensor_helpers::cameraImageOrientationMap)); - int expLimit = declareAndLogParam("r_auto_exposure_limit", 1000); + int expLimit = declareAndLogParam("r_auto_exposure_limit", 1000); if(declareAndLogParam("r_set_auto_exposure_limit", false)) { monoCam->initialControl.setAutoExposureLimit(expLimit); } - int sharpness = declareAndLogParam("r_sharpness", 1); + int sharpness = declareAndLogParam("r_sharpness", 1); if(declareAndLogParam("r_set_sharpness", false)) { monoCam->initialControl.setSharpness(sharpness); } - int chromaDenoise = declareAndLogParam("r_chroma_denoise", 1); + int chromaDenoise = declareAndLogParam("r_chroma_denoise", 1); if(declareAndLogParam("r_set_chroma_denoise", false)) { monoCam->initialControl.setChromaDenoise(chromaDenoise); } - int lumaDenoise = declareAndLogParam("r_luma_denoise", 1); + int lumaDenoise = declareAndLogParam("r_luma_denoise", 1); if(declareAndLogParam("r_set_luma_denoise", false)) { monoCam->initialControl.setLumaDenoise(lumaDenoise); } @@ -194,19 +194,19 @@ void SensorParamHandler::declareParams(std::shared_ptr c } colorCam->setImageOrientation( utils::getValFromMap(declareAndLogParam("i_sensor_img_orientation", "AUTO"), dai_nodes::sensor_helpers::cameraImageOrientationMap)); - int expLimit = declareAndLogParam("r_auto_exposure_limit", 1000); + int expLimit = declareAndLogParam("r_auto_exposure_limit", 1000); if(declareAndLogParam("r_set_auto_exposure_limit", false)) { colorCam->initialControl.setAutoExposureLimit(expLimit); } - int sharpness = declareAndLogParam("r_sharpness", 1); + int sharpness = declareAndLogParam("r_sharpness", 1); if(declareAndLogParam("r_set_sharpness", false)) { colorCam->initialControl.setSharpness(sharpness); } - int chromaDenoise = declareAndLogParam("r_chroma_denoise", 1); + int chromaDenoise = declareAndLogParam("r_chroma_denoise", 1); if(declareAndLogParam("r_set_chroma_denoise", false)) { colorCam->initialControl.setChromaDenoise(chromaDenoise); } - int lumaDenoise = declareAndLogParam("r_luma_denoise", 1); + int lumaDenoise = declareAndLogParam("r_luma_denoise", 1); if(declareAndLogParam("r_set_luma_denoise", false)) { colorCam->initialControl.setLumaDenoise(lumaDenoise); } diff --git a/depthai_ros_driver/src/param_handlers/stereo_param_handler.cpp b/depthai_ros_driver/src/param_handlers/stereo_param_handler.cpp index 5c6c0b58..c5cd93c3 100644 --- a/depthai_ros_driver/src/param_handlers/stereo_param_handler.cpp +++ b/depthai_ros_driver/src/param_handlers/stereo_param_handler.cpp @@ -1,5 +1,7 @@ #include "depthai_ros_driver/param_handlers/stereo_param_handler.hpp" +#include + #include "depthai-shared/common/CameraFeatures.hpp" #include "depthai/pipeline/datatype/StereoDepthConfig.hpp" #include "depthai/pipeline/node/StereoDepth.hpp" @@ -10,10 +12,12 @@ namespace depthai_ros_driver { namespace param_handlers { StereoParamHandler::StereoParamHandler(std::shared_ptr node, const std::string& name) : BaseParamHandler(node, name) { - depthPresetMap = { - {"HIGH_ACCURACY", dai::node::StereoDepth::PresetMode::HIGH_ACCURACY}, - {"HIGH_DENSITY", dai::node::StereoDepth::PresetMode::HIGH_DENSITY}, - }; + depthPresetMap = {{"HIGH_ACCURACY", dai::node::StereoDepth::PresetMode::HIGH_ACCURACY}, + {"HIGH_DENSITY", dai::node::StereoDepth::PresetMode::HIGH_DENSITY}, + {"DEFAULT", dai::node::StereoDepth::PresetMode::DEFAULT}, + {"FACE", dai::node::StereoDepth::PresetMode::FACE}, + {"HIGH_DETAIL", dai::node::StereoDepth::PresetMode::HIGH_DETAIL}, + {"ROBOTICS", dai::node::StereoDepth::PresetMode::ROBOTICS}}; disparityWidthMap = { {"DISPARITY_64", dai::StereoDepthConfig::CostMatching::DisparityWidth::DISPARITY_64}, @@ -139,34 +143,35 @@ void StereoParamHandler::declareParams(std::shared_ptr s if(declareAndLogParam("i_subpixel", true) && !lowBandwidth) { stereo->initialConfig.setSubpixel(true); stereo->initialConfig.setSubpixelFractionalBits(declareAndLogParam("i_subpixel_fractional_bits", 3)); - } - else if(lowBandwidth) { + } else { + stereo->initialConfig.setSubpixel(false); RCLCPP_INFO(getROSNode()->get_logger(), "Subpixel disabled due to low bandwidth mode"); } stereo->setRectifyEdgeFillColor(declareAndLogParam("i_rectify_edge_fill_color", 0)); if(declareAndLogParam("i_enable_alpha_scaling", false)) { stereo->setAlphaScaling(declareAndLogParam("i_alpha_scaling", 0.0)); } - auto config = stereo->initialConfig.get(); + dai::RawStereoDepthConfig config = stereo->initialConfig.get(); config.costMatching.disparityWidth = utils::getValFromMap(declareAndLogParam("i_disparity_width", "DISPARITY_96"), disparityWidthMap); stereo->setExtendedDisparity(declareAndLogParam("i_extended_disp", false)); config.costMatching.enableCompanding = declareAndLogParam("i_enable_companding", false); - config.postProcessing.temporalFilter.enable = declareAndLogParam("i_enable_temporal_filter", false); - if(config.postProcessing.temporalFilter.enable) { + if(declareAndLogParam("i_enable_temporal_filter", false)) { + config.postProcessing.temporalFilter.enable = true; config.postProcessing.temporalFilter.alpha = declareAndLogParam("i_temporal_filter_alpha", 0.4); config.postProcessing.temporalFilter.delta = declareAndLogParam("i_temporal_filter_delta", 20); config.postProcessing.temporalFilter.persistencyMode = utils::getValFromMap(declareAndLogParam("i_temporal_filter_persistency", "VALID_2_IN_LAST_4"), temporalPersistencyMap); } - config.postProcessing.speckleFilter.enable = declareAndLogParam("i_enable_speckle_filter", false); - if(config.postProcessing.speckleFilter.enable) { + if(declareAndLogParam("i_enable_speckle_filter", false)) { + config.postProcessing.speckleFilter.enable = true; config.postProcessing.speckleFilter.speckleRange = declareAndLogParam("i_speckle_filter_speckle_range", 50); } if(declareAndLogParam("i_enable_disparity_shift", false)) { config.algorithmControl.disparityShift = declareAndLogParam("i_disparity_shift", 0); } - config.postProcessing.spatialFilter.enable = declareAndLogParam("i_enable_spatial_filter", false); - if(config.postProcessing.spatialFilter.enable) { + + if(declareAndLogParam("i_enable_spatial_filter", false)) { + config.postProcessing.spatialFilter.enable = true; config.postProcessing.spatialFilter.holeFillingRadius = declareAndLogParam("i_spatial_filter_hole_filling_radius", 2); config.postProcessing.spatialFilter.alpha = declareAndLogParam("i_spatial_filter_alpha", 0.5); config.postProcessing.spatialFilter.delta = declareAndLogParam("i_spatial_filter_delta", 20); diff --git a/depthai_ros_msgs/CMakeLists.txt b/depthai_ros_msgs/CMakeLists.txt index 78cc0232..d027a765 100644 --- a/depthai_ros_msgs/CMakeLists.txt +++ b/depthai_ros_msgs/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.10.2) # CMake version in Ubuntu 18.04 LTS -project(depthai_ros_msgs VERSION 2.10.4) +project(depthai_ros_msgs VERSION 2.10.5) if(POLICY CMP0057) cmake_policy(SET CMP0057 NEW) diff --git a/depthai_ros_msgs/package.xml b/depthai_ros_msgs/package.xml index 51e13e9d..f455901d 100644 --- a/depthai_ros_msgs/package.xml +++ b/depthai_ros_msgs/package.xml @@ -1,7 +1,7 @@ depthai_ros_msgs - 2.10.4 + 2.10.5 Package to keep interface independent of the driver Adam Serafin