Skip to content

Commit

Permalink
Fix lowbandwidth & add stereo filters - Humble (#651)
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam authored Jan 10, 2025
1 parent 55739e2 commit cf71d9d
Show file tree
Hide file tree
Showing 24 changed files with 67 additions and 48 deletions.
6 changes: 6 additions & 0 deletions depthai-ros/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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)
-------------------
Expand Down
2 changes: 1 addition & 1 deletion depthai-ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)

Expand Down
2 changes: 1 addition & 1 deletion depthai-ros/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>depthai-ros</name>
<version>2.10.4</version>
<version>2.10.5</version>
<description>The depthai-ros package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
Expand Down
4 changes: 3 additions & 1 deletion depthai_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)
Expand All @@ -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)
Expand All @@ -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
Expand Down
2 changes: 1 addition & 1 deletion depthai_bridge/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>depthai_bridge</name>
<version>2.10.4</version>
<version>2.10.5</version>
<description>The depthai_bridge package</description>

<maintainer email="[email protected]">Adam Serafin</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion depthai_bridge/src/TFPublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@ std::string TFPublisher::getURDF() {
RCLCPP_DEBUG(logger, "Xacro command: %s", cmd.c_str());
std::array<char, 128> buffer;
std::string result;
std::unique_ptr<FILE, decltype(&pclose)> pipe(popen(cmd.c_str(), "r"), pclose);
std::unique_ptr<FILE, int (*)(FILE*)> pipe(popen(cmd.c_str(), "r"), pclose);
if(!pipe) {
throw std::runtime_error("popen() failed!");
}
Expand Down
2 changes: 1 addition & 1 deletion depthai_descriptions/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)
Expand Down
2 changes: 1 addition & 1 deletion depthai_descriptions/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>depthai_descriptions</name>
<version>2.10.4</version>
<version>2.10.5</version>
<description>The depthai_descriptions package</description>

<maintainer email="[email protected]">Adam Serafin</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion depthai_examples/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)
Expand Down
2 changes: 1 addition & 1 deletion depthai_examples/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>depthai_examples</name>
<version>2.10.4</version>
<version>2.10.5</version>
<description>The depthai_examples package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
Expand Down
2 changes: 1 addition & 1 deletion depthai_filters/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)
Expand Down
2 changes: 1 addition & 1 deletion depthai_filters/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>depthai_filters</name>
<version>2.10.4</version>
<version>2.10.5</version>
<description>Depthai filters package</description>
<maintainer email="[email protected]">Adam Serafin</maintainer>
<license>MIT</license>
Expand Down
4 changes: 2 additions & 2 deletions depthai_filters/src/detection2d_overlay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<message_filters::Synchronizer<syncPolicy>>(syncPolicy(10), previewSub, detSub);
sync->registerCallback(std::bind(&Detection2DOverlay::overlayCB, this, std::placeholders::_1, std::placeholders::_2 ));
sync = std::make_unique<message_filters::Synchronizer<syncPolicy>>(syncPolicy(10), previewSub, detSub);
sync->registerCallback(std::bind(&Detection2DOverlay::overlayCB, this, std::placeholders::_1, std::placeholders::_2));
overlayPub = this->create_publisher<sensor_msgs::msg::Image>("overlay", 10);
labelMap = this->declare_parameter<std::vector<std::string>>("label_map", labelMap);
}
Expand Down
2 changes: 1 addition & 1 deletion depthai_ros_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<dai::CameraBoardSocket>(ph->getParam<int>("i_board_socket_id"));

ptPub->setup(device, convConf, pubConf);
Expand All @@ -98,7 +98,7 @@ class SpatialDetection : public BaseNode {
pubConf.height = ph->getOtherNodeParam<int>(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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class NNParamHandler : public BaseParamHandler {
template <typename T>
void declareParams(std::shared_ptr<T> nn, std::shared_ptr<dai::node::ImageManip> imageManip) {
declareAndLogParam<bool>("i_disable_resize", false);
declareAndLogParam<bool>("i_desqueeze_output", false);
declareAndLogParam<bool>("i_desqueeze_output", false);
declareAndLogParam<bool>("i_enable_passthrough", false);
declareAndLogParam<bool>("i_enable_passthrough_depth", false);
declareAndLogParam<bool>("i_get_base_device_timestamp", false);
Expand Down
3 changes: 2 additions & 1 deletion depthai_ros_driver/include/depthai_ros_driver/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion depthai_ros_driver/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>depthai_ros_driver</name>
<version>2.10.4</version>
<version>2.10.5</version>
<description>Depthai ROS Monolithic node.</description>
<maintainer email="[email protected]">Adam Serafin</maintainer>

Expand Down
14 changes: 9 additions & 5 deletions depthai_ros_driver/src/dai_nodes/sensors/img_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,12 @@ void ImagePublisher::setup(std::shared_ptr<dai::Device> device, const utils::Img
ffmpegPub = node->create_publisher<ffmpeg_image_transport_msgs::msg::FFMPEGPacket>(
pubConfig.topicName + pubConfig.compressedTopicSuffix, rclcpp::QoS(10), pubOptions);
}
infoPub = node->create_publisher<sensor_msgs::msg::CameraInfo>(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions);
infoPub =
node->create_publisher<sensor_msgs::msg::CameraInfo>(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions);
} else if(ipcEnabled) {
imgPub = node->create_publisher<sensor_msgs::msg::Image>(pubConfig.topicName + pubConfig.topicSuffix, rclcpp::QoS(10), pubOptions);
infoPub = node->create_publisher<sensor_msgs::msg::CameraInfo>(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions);
infoPub =
node->create_publisher<sensor_msgs::msg::CameraInfo>(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions);
} else {
imgPubIT = image_transport::create_camera_publisher(node.get(), pubConfig.topicName + pubConfig.topicSuffix);
}
Expand All @@ -97,7 +99,7 @@ void ImagePublisher::createImageConverter(std::shared_ptr<dai::Device> 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) {
Expand All @@ -113,8 +115,10 @@ std::shared_ptr<dai::node::VideoEncoder> ImagePublisher::createEncoder(std::shar
auto enc = pipeline->create<dai::node::VideoEncoder>();
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<dai::Device> device) {
Expand Down
3 changes: 2 additions & 1 deletion depthai_ros_driver/src/dai_nodes/sensors/stereo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -194,11 +194,12 @@ void Stereo::setupStereoQueue(std::shared_ptr<dai::Device> device) {
convConfig.alphaScaling = ph->getParam<double>("i_alpha_scaling");
}
convConfig.outputDisparity = ph->getParam<bool>("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<int>("i_width");
pubConf.height = ph->getParam<int>("i_height");
Expand Down
16 changes: 8 additions & 8 deletions depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,19 +79,19 @@ void SensorParamHandler::declareParams(std::shared_ptr<dai::node::MonoCamera> mo
}
monoCam->setImageOrientation(
utils::getValFromMap(declareAndLogParam<std::string>("i_sensor_img_orientation", "AUTO"), dai_nodes::sensor_helpers::cameraImageOrientationMap));
int expLimit = declareAndLogParam<int>("r_auto_exposure_limit", 1000);
int expLimit = declareAndLogParam<int>("r_auto_exposure_limit", 1000);
if(declareAndLogParam<bool>("r_set_auto_exposure_limit", false)) {
monoCam->initialControl.setAutoExposureLimit(expLimit);
}
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
if(declareAndLogParam("r_set_sharpness", false)) {
monoCam->initialControl.setSharpness(sharpness);
}
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
if(declareAndLogParam("r_set_chroma_denoise", false)) {
monoCam->initialControl.setChromaDenoise(chromaDenoise);
}
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
if(declareAndLogParam("r_set_luma_denoise", false)) {
monoCam->initialControl.setLumaDenoise(lumaDenoise);
}
Expand Down Expand Up @@ -194,19 +194,19 @@ void SensorParamHandler::declareParams(std::shared_ptr<dai::node::ColorCamera> c
}
colorCam->setImageOrientation(
utils::getValFromMap(declareAndLogParam<std::string>("i_sensor_img_orientation", "AUTO"), dai_nodes::sensor_helpers::cameraImageOrientationMap));
int expLimit = declareAndLogParam<int>("r_auto_exposure_limit", 1000);
int expLimit = declareAndLogParam<int>("r_auto_exposure_limit", 1000);
if(declareAndLogParam<bool>("r_set_auto_exposure_limit", false)) {
colorCam->initialControl.setAutoExposureLimit(expLimit);
}
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
int sharpness = declareAndLogParam<int>("r_sharpness", 1);
if(declareAndLogParam("r_set_sharpness", false)) {
colorCam->initialControl.setSharpness(sharpness);
}
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
int chromaDenoise = declareAndLogParam<int>("r_chroma_denoise", 1);
if(declareAndLogParam("r_set_chroma_denoise", false)) {
colorCam->initialControl.setChromaDenoise(chromaDenoise);
}
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
int lumaDenoise = declareAndLogParam<int>("r_luma_denoise", 1);
if(declareAndLogParam("r_set_luma_denoise", false)) {
colorCam->initialControl.setLumaDenoise(lumaDenoise);
}
Expand Down
31 changes: 18 additions & 13 deletions depthai_ros_driver/src/param_handlers/stereo_param_handler.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include "depthai_ros_driver/param_handlers/stereo_param_handler.hpp"

#include <depthai-shared/datatype/RawStereoDepthConfig.hpp>

#include "depthai-shared/common/CameraFeatures.hpp"
#include "depthai/pipeline/datatype/StereoDepthConfig.hpp"
#include "depthai/pipeline/node/StereoDepth.hpp"
Expand All @@ -10,10 +12,12 @@
namespace depthai_ros_driver {
namespace param_handlers {
StereoParamHandler::StereoParamHandler(std::shared_ptr<rclcpp::Node> 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},
Expand Down Expand Up @@ -139,34 +143,35 @@ void StereoParamHandler::declareParams(std::shared_ptr<dai::node::StereoDepth> s
if(declareAndLogParam<bool>("i_subpixel", true) && !lowBandwidth) {
stereo->initialConfig.setSubpixel(true);
stereo->initialConfig.setSubpixelFractionalBits(declareAndLogParam<int>("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<int>("i_rectify_edge_fill_color", 0));
if(declareAndLogParam<bool>("i_enable_alpha_scaling", false)) {
stereo->setAlphaScaling(declareAndLogParam<float>("i_alpha_scaling", 0.0));
}
auto config = stereo->initialConfig.get();
dai::RawStereoDepthConfig config = stereo->initialConfig.get();
config.costMatching.disparityWidth = utils::getValFromMap(declareAndLogParam<std::string>("i_disparity_width", "DISPARITY_96"), disparityWidthMap);
stereo->setExtendedDisparity(declareAndLogParam<bool>("i_extended_disp", false));
config.costMatching.enableCompanding = declareAndLogParam<bool>("i_enable_companding", false);
config.postProcessing.temporalFilter.enable = declareAndLogParam<bool>("i_enable_temporal_filter", false);
if(config.postProcessing.temporalFilter.enable) {
if(declareAndLogParam<bool>("i_enable_temporal_filter", false)) {
config.postProcessing.temporalFilter.enable = true;
config.postProcessing.temporalFilter.alpha = declareAndLogParam<float>("i_temporal_filter_alpha", 0.4);
config.postProcessing.temporalFilter.delta = declareAndLogParam<int>("i_temporal_filter_delta", 20);
config.postProcessing.temporalFilter.persistencyMode =
utils::getValFromMap(declareAndLogParam<std::string>("i_temporal_filter_persistency", "VALID_2_IN_LAST_4"), temporalPersistencyMap);
}
config.postProcessing.speckleFilter.enable = declareAndLogParam<bool>("i_enable_speckle_filter", false);
if(config.postProcessing.speckleFilter.enable) {
if(declareAndLogParam<bool>("i_enable_speckle_filter", false)) {
config.postProcessing.speckleFilter.enable = true;
config.postProcessing.speckleFilter.speckleRange = declareAndLogParam<int>("i_speckle_filter_speckle_range", 50);
}
if(declareAndLogParam<bool>("i_enable_disparity_shift", false)) {
config.algorithmControl.disparityShift = declareAndLogParam<int>("i_disparity_shift", 0);
}
config.postProcessing.spatialFilter.enable = declareAndLogParam<bool>("i_enable_spatial_filter", false);
if(config.postProcessing.spatialFilter.enable) {

if(declareAndLogParam<bool>("i_enable_spatial_filter", false)) {
config.postProcessing.spatialFilter.enable = true;
config.postProcessing.spatialFilter.holeFillingRadius = declareAndLogParam<int>("i_spatial_filter_hole_filling_radius", 2);
config.postProcessing.spatialFilter.alpha = declareAndLogParam<float>("i_spatial_filter_alpha", 0.5);
config.postProcessing.spatialFilter.delta = declareAndLogParam<int>("i_spatial_filter_delta", 20);
Expand Down
2 changes: 1 addition & 1 deletion depthai_ros_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)
Expand Down
2 changes: 1 addition & 1 deletion depthai_ros_msgs/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>depthai_ros_msgs</name>
<version>2.10.4</version>
<version>2.10.5</version>
<description>Package to keep interface independent of the driver</description>

<maintainer email="[email protected]">Adam Serafin</maintainer>
Expand Down

0 comments on commit cf71d9d

Please sign in to comment.