Skip to content

Commit

Permalink
273 noetic (#337)
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam authored Jun 21, 2023
1 parent 35786e4 commit d328827
Show file tree
Hide file tree
Showing 35 changed files with 656 additions and 272 deletions.
12 changes: 11 additions & 1 deletion depthai-ros/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,17 @@
Changelog for package depthai-ros
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.7.2 (20230-5-08)
2.7.3 (2023-06-16)
-------------------
* Pipeline generation as a plugin
* Fixed bounding box generation issue
* Stereo rectified streams publishing
* Camera trigger mechanisms
* Brightness filter


2.7.2 (2023-5-08)
-------------------
* IMU improvements

2.7.1 (2023-03-29)
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.7.2 LANGUAGES CXX C)
project(depthai-ros VERSION 2.7.3 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.7.2</version>
<version>2.7.3</version>
<description>The depthai-ros package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
Expand Down
2 changes: 1 addition & 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.7.2 LANGUAGES CXX C)
project(depthai_bridge VERSION 2.7.3 LANGUAGES CXX C)

set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
Expand Down
15 changes: 11 additions & 4 deletions depthai_bridge/include/depthai_bridge/ImuConverter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,8 @@ class ImuConverter {
double angular_velocity_cov = 0.0,
double rotation_cov = 0.0,
double magnetic_field_cov = 0.0,
bool enable_rotation = false);
bool enable_rotation = false,
bool getBaseDeviceTimestamp = false);
~ImuConverter();

/**
Expand Down Expand Up @@ -132,6 +133,7 @@ class ImuConverter {
int64_t _totalNsChange{0};
// Whether to update the ROS base time on each message conversion
bool _updateRosBaseTimeOnToRosMsg{false};
bool _getBaseDeviceTimestamp;

void fillImuMsg(dai::IMUReportAccelerometer report, ImuMsgs::Imu& msg);
void fillImuMsg(dai::IMUReportGyroscope report, ImuMsgs::Imu& msg);
Expand All @@ -144,15 +146,15 @@ class ImuConverter {
void fillImuMsg(dai::IMUReportMagneticField report, depthai_ros_msgs::ImuWithMagneticField& msg);

template <typename I, typename S, typename T, typename F, typename M>
void CreateUnitMessage(I first, S second, T third, F fourth, M& msg, dai::Timestamp timestamp) {
void CreateUnitMessage(I first, S second, T third, F fourth, M& msg, std::chrono::_V2::steady_clock::time_point timestamp) {
fillImuMsg(first, msg);
fillImuMsg(second, msg);
fillImuMsg(third, msg);
fillImuMsg(fourth, msg);

msg.header.frame_id = _frameName;

msg.header.stamp = getFrameTime(_rosBaseTime, _steadyBaseTime, timestamp.get());
msg.header.stamp = getFrameTime(_rosBaseTime, _steadyBaseTime, timestamp);
}

template <typename I, typename S, typename T, typename F, typename M>
Expand Down Expand Up @@ -182,7 +184,12 @@ class ImuConverter {
const double alpha = diff.count() / dt;
I interp = lerpImu(interp0, interp1, alpha);
M msg;
CreateUnitMessage(interp, currSecond, currThird, currFourth, msg, currSecond.timestamp);
std::chrono::_V2::steady_clock::time_point tstamp;
if(_getBaseDeviceTimestamp)
tstamp = currSecond.getTimestampDevice();
else
tstamp = currSecond.getTimestamp();
CreateUnitMessage(interp, currSecond, currThird, currFourth, msg, tstamp);
imuMsgs.push_back(msg);
second.pop_front();
third.pop_front();
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.7.2</version>
<version>2.7.3</version>
<description>The depthai_bridge package</description>

<maintainer email="[email protected]">Sachin Guruswamy</maintainer>
Expand Down
22 changes: 18 additions & 4 deletions depthai_bridge/src/ImuConverter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@ ImuConverter::ImuConverter(const std::string& frameName,
double angular_velocity_cov,
double rotation_cov,
double magnetic_field_cov,
bool enable_rotation)
bool enable_rotation,
bool getBaseDeviceTimestamp)
: _frameName(frameName),
_syncMode(syncMode),
_linear_accel_cov(linear_accel_cov),
Expand All @@ -22,7 +23,8 @@ ImuConverter::ImuConverter(const std::string& frameName,
_magnetic_field_cov(magnetic_field_cov),
_enable_rotation(enable_rotation),
_sequenceNum(0),
_steadyBaseTime(std::chrono::steady_clock::now()) {
_steadyBaseTime(std::chrono::steady_clock::now()),
_getBaseDeviceTimestamp(getBaseDeviceTimestamp) {
_rosBaseTime = ::ros::Time::now();
}

Expand Down Expand Up @@ -98,7 +100,13 @@ void ImuConverter::toRosMsg(std::shared_ptr<dai::IMUData> inData, std::deque<Imu
auto rot = inData->packets[i].rotationVector;
auto magn = inData->packets[i].magneticField;
ImuMsgs::Imu msg;
CreateUnitMessage(accel, gyro, rot, magn, msg, accel.timestamp);
std::chrono::_V2::steady_clock::time_point tstamp;
if(_getBaseDeviceTimestamp)
tstamp = accel.getTimestampDevice();
else
tstamp = accel.getTimestamp();

CreateUnitMessage(accel, gyro, rot, magn, msg, tstamp);
outImuMsgs.push_back(msg);
}
}
Expand All @@ -114,7 +122,13 @@ void ImuConverter::toRosDaiMsg(std::shared_ptr<dai::IMUData> inData, std::deque<
auto rot = inData->packets[i].rotationVector;
auto magn = inData->packets[i].magneticField;
depthai_ros_msgs::ImuWithMagneticField msg;
CreateUnitMessage(accel, gyro, rot, magn, msg, accel.timestamp);
std::chrono::_V2::steady_clock::time_point tstamp;
if(_getBaseDeviceTimestamp)
tstamp = accel.getTimestampDevice();
else
tstamp = accel.getTimestamp();

CreateUnitMessage(accel, gyro, rot, magn, msg, tstamp);
outImuMsgs.push_back(msg);
}
}
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.10.2)
project(depthai_descriptions VERSION 2.7.2 LANGUAGES CXX C)
project(depthai_descriptions VERSION 2.7.3 LANGUAGES CXX C)


find_package(catkin REQUIRED
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="2">
<name>depthai_descriptions</name>
<version>2.7.2</version>
<version>2.7.3</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.7.2 LANGUAGES CXX C)
project(depthai_examples VERSION 2.7.3 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.7.2</version>
<version>2.7.3</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.10.2)
project(depthai_filters VERSION 2.7.2 LANGUAGES CXX C)
project(depthai_filters VERSION 2.7.3 LANGUAGES CXX C)

set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
Expand Down
2 changes: 1 addition & 1 deletion depthai_filters/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>depthai_filters</name>
<version>2.7.2</version>
<version>2.7.3</version>
<description>The depthai_filters package</description>

<maintainer email="[email protected]">Adam Serafin</maintainer>
Expand Down
7 changes: 5 additions & 2 deletions depthai_ros_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,6 @@ include_directories(
${OpenCV_INCLUDE_DIRS}
)

include_directories(include)

catkin_package(
LIBRARIES
Expand Down Expand Up @@ -134,8 +133,9 @@ target_link_libraries(

add_library(
${PROJECT_NAME} SHARED
src/pipeline/pipeline_generator.cpp
src/pipeline/base_types.cpp
src/camera.cpp
src/pipeline_generator.cpp
)


Expand Down Expand Up @@ -177,6 +177,9 @@ install(
DESTINATION lib/${PROJECT_NAME}
)

install(FILES plugins.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

install(
DIRECTORY include/
DESTINATION include
Expand Down
13 changes: 12 additions & 1 deletion depthai_ros_driver/cfg/parameters.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ camera.add("rgb_i_board_socket_id", int_t, 0, "Sensor board socket id", 0)
camera.add("rgb_i_calibration_file", str_t, 0, "Path to calibration file", "")
camera.add("rgb_i_fps", double_t, 0, "FPS", 60.0)
camera.add("rgb_i_height", int_t, 0, "Image height", 720)
camera.add("rgb_i_interleaved", bool_t, 0, "Is frame interleaved or planar", True)
camera.add("rgb_i_interleaved", bool_t, 0, "Is frame interleaved or planar", False)
camera.add("rgb_r_keep_preview_aspect_ratio", bool_t, 0, "Keep preview aspect ratio", True)
camera.add("rgb_i_low_bandwidth", bool_t, 0, "Use encoding for data", False)
camera.add("rgb_i_low_bandwidth_quality", int_t, 0, "Quality when using low-bandwidth mode", 50, 1, 100)
Expand Down Expand Up @@ -116,6 +116,9 @@ camera.add("stereo_i_decimation_filter_decimation_factor", int_t, 0, "Decimation
camera.add("stereo_i_decimation_filter_decimation_mode", str_t, 0, "Decimation mode", "PIXEL_SKIPPING")
camera.add("stereo_i_depth_filter_size", int_t, 0, "Depth filter size", 5)
camera.add("stereo_i_depth_preset", str_t, 0, "Depth preset", "HIGH_ACCURACY")
camera.add("stereo_i_enable_brightness_filter", bool_t, 0, "Enable brightness filter", False)
camera.add("stereo_i_brightness_filter_min_brightness", int_t, 0, "Brightness filter min", 0)
camera.add("stereo_i_brightness_filter_max_brightness", int_t, 0, "Brightness filter max", 256)
camera.add("stereo_i_enable_companding", bool_t, 0, "Enable companding", False)
camera.add("stereo_i_enable_decimation_filter", bool_t, 0, "Enable decimation filter", False)
camera.add("stereo_i_enable_distortion_correction", bool_t, 0, "Enable distortion correction", True)
Expand All @@ -129,6 +132,13 @@ camera.add("stereo_i_low_bandwidth_quality", int_t, 0, "Quality when using low-b
camera.add("stereo_i_lr_check", bool_t, 0, "Enable left-right check", True)
camera.add("stereo_i_lrc_threshold", int_t, 0, "Left-right check threshold", 10)
camera.add("stereo_i_max_q_size", int_t, 0, "Internal queue size", 30)
camera.add("stereo_i_publish_left_rect", bool_t, 0, "Publish rectified left", False)
camera.add("stereo_i_left_rect_low_bandwidth", bool_t, 0, "Low bandwidth for rectified left", False)
camera.add("stereo_i_left_rect_low_bandwidth_quality", int_t, 0, "Low bandwidth left quality", 50)
camera.add("stereo_i_publish_right_rect", bool_t, 0, "Publish rectified right", False)
camera.add("stereo_i_right_rect_low_bandwidth", bool_t, 0, "Low bandwidth for rectified right", False)
camera.add("stereo_i_right_rect_low_bandwidth_quality", int_t, 0, "Low bandwidth right quality", 50)
camera.add("stereo_i_publish_topic", bool_t, 0, "Publish stereo topic", True)
camera.add("stereo_i_rectify_edge_fill_color", int_t, 0, "Rectify edge fill color", 0)
camera.add("stereo_i_spatial_filter_alpha", double_t, 0, "Spatial filter alpha", 0.5)
camera.add("stereo_i_spatial_filter_delta", int_t, 0, "Spatial filter delta", 20)
Expand Down Expand Up @@ -159,6 +169,7 @@ camera.add("imu_i_acc_freq", int_t, 0, "Accelerometer frequency", 500)
camera.add("imu_i_acc_cov", double_t, 0, "Accelerometer covariance", 0.0)
camera.add("imu_i_batch_report_threshold", int_t, 0, "Batch report size", 5)
camera.add("imu_i_enable_rotation", bool_t, 0, "Whether to enable rotation vector & magnetometer data (available when using IMU_WITH_MAGN/ IMU_WITH_MAGN_SPLIT message type)", False)
camera.add("imu_i_get_base_device_timestamp", bool_t, 0, "Use base device timestamp", False)
camera.add("imu_i_gyro_cov", double_t, 0, "Gyroscope covariance", 0.0)
camera.add("imu_i_gyro_freq", int_t, 0, "Gyroscope frequency", 400)
camera.add("imu_i_mag_cov", double_t, 0, "Magnetometer covariance", 0.0)
Expand Down
4 changes: 2 additions & 2 deletions depthai_ros_driver/config/camera.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
left_i_preview_size: 300
left_i_publish_topic: false
left_i_resolution: '720'
left_i_set_isp_scale: false
left_i_set_isp_scale: true
left_i_width: 1280
left_r_exposure: 1000
left_r_focus: 1
Expand Down Expand Up @@ -67,7 +67,7 @@
right_i_preview_size: 300
right_i_publish_topic: false
right_i_resolution: '720'
right_i_set_isp_scale: false
right_i_set_isp_scale: true
right_i_width: 1280
right_r_exposure: 1000
right_r_focus: 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,20 +44,25 @@ class Detection : public BaseNode {
void setupQueues(std::shared_ptr<dai::Device> device) override {
nnQ = device->getOutputQueue(nnQName, ph->getParam<int>("i_max_q_size"), false);
auto tfPrefix = getTFPrefix("rgb");
detConverter = std::make_unique<dai::ros::ImgDetectionConverter>(tfPrefix + "_camera_optical_frame",
imageManip->initialConfig.getResizeConfig().width,
imageManip->initialConfig.getResizeConfig().height,
false,
ph->getParam<bool>("i_get_base_device_timestamp"));
int width;
int height;
if(ph->getParam<bool>("i_disable_resize")) {
width = ph->getOtherNodeParam<int>("rgb", "i_preview_size");
height = ph->getOtherNodeParam<int>("rgb", "i_preview_size");
} else {
width = imageManip->initialConfig.getResizeConfig().width;
height = imageManip->initialConfig.getResizeConfig().height;
}
detConverter = std::make_unique<dai::ros::ImgDetectionConverter>(
tfPrefix + "_camera_optical_frame", width, height, false, ph->getParam<bool>("i_get_base_device_timestamp"));
detPub = getROSNode().template advertise<vision_msgs::Detection2DArray>(getName() + "/detections", 10);
nnQ->addCallback(std::bind(&Detection::detectionCB, this, std::placeholders::_1, std::placeholders::_2));

if(ph->getParam<bool>("i_enable_passthrough")) {
ptQ = device->getOutputQueue(ptQName, ph->getParam<int>("i_max_q_size"), false);
imageConverter = std::make_unique<dai::ros::ImageConverter>(tfPrefix + "_camera_optical_frame", false);
infoManager = std::make_shared<camera_info_manager::CameraInfoManager>(ros::NodeHandle(getROSNode(), getName()), "/" + getName());
infoManager->setCameraInfo(sensor_helpers::getCalibInfo(
*imageConverter, device, dai::CameraBoardSocket::RGB, imageManip->initialConfig.getResizeWidth(), imageManip->initialConfig.getResizeWidth()));
infoManager->setCameraInfo(sensor_helpers::getCalibInfo(*imageConverter, device, dai::CameraBoardSocket::RGB, width, height));

ptPub = it.advertiseCamera(getName() + "/passthrough/image_raw", 1);
ptQ->addCallback(std::bind(sensor_helpers::imgCB, std::placeholders::_1, std::placeholders::_2, *imageConverter, ptPub, infoManager));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,23 +47,25 @@ class SpatialDetection : public BaseNode {
void setupQueues(std::shared_ptr<dai::Device> device) override {
nnQ = device->getOutputQueue(nnQName, ph->getParam<int>("i_max_q_size"), false);
auto tfPrefix = getTFPrefix("rgb");
detConverter = std::make_unique<dai::ros::SpatialDetectionConverter>(tfPrefix + "_camera_optical_frame",
imageManip->initialConfig.getResizeConfig().width,
imageManip->initialConfig.getResizeConfig().height,
false,
ph->getParam<bool>("i_get_base_device_timestamp"));
int width;
int height;
if(ph->getParam<bool>("i_disable_resize")) {
width = ph->getOtherNodeParam<int>("rgb", "i_preview_size");
height = ph->getOtherNodeParam<int>("rgb", "i_preview_size");
} else {
width = imageManip->initialConfig.getResizeConfig().width;
height = imageManip->initialConfig.getResizeConfig().height;
}
detConverter = std::make_unique<dai::ros::SpatialDetectionConverter>(
tfPrefix + "_camera_optical_frame", width, height, false, ph->getParam<bool>("i_get_base_device_timestamp"));
nnQ->addCallback(std::bind(&SpatialDetection::spatialCB, this, std::placeholders::_1, std::placeholders::_2));
detPub = getROSNode().template advertise<vision_msgs::Detection3DArray>(getName() + "/spatial_detections", 10);

if(ph->getParam<bool>("i_enable_passthrough")) {
ptQ = device->getOutputQueue(ptQName, ph->getParam<int>("i_max_q_size"), false);
ptImageConverter = std::make_unique<dai::ros::ImageConverter>(tfPrefix + "_camera_optical_frame", false);
ptInfoMan = std::make_shared<camera_info_manager::CameraInfoManager>(ros::NodeHandle(getROSNode(), getName()), "/" + getName());
ptInfoMan->setCameraInfo(sensor_helpers::getCalibInfo(*ptImageConverter,
device,
dai::CameraBoardSocket::RGB,
imageManip->initialConfig.getResizeWidth(),
imageManip->initialConfig.getResizeWidth()));
ptInfoMan->setCameraInfo(sensor_helpers::getCalibInfo(*ptImageConverter, device, dai::CameraBoardSocket::RGB, width, height));

ptPub = it.advertiseCamera(getName() + "/passthrough/image_raw", 1);
ptQ->addCallback(std::bind(sensor_helpers::imgCB, std::placeholders::_1, std::placeholders::_2, *ptImageConverter, ptPub, ptInfoMan));
Expand All @@ -80,9 +82,8 @@ class SpatialDetection : public BaseNode {
ptDepthQ = device->getOutputQueue(ptDepthQName, ph->getParam<int>("i_max_q_size"), false);
ptDepthImageConverter = std::make_unique<dai::ros::ImageConverter>(tfPrefix + "_camera_optical_frame", false);
ptDepthInfoMan = std::make_shared<camera_info_manager::CameraInfoManager>(ros::NodeHandle(getROSNode(), getName()), "/" + getName());
int width, height;
getROSNode().getParam("stereo_i_width", width);
getROSNode().getParam("stereo_i_height", height);
int width = ph->getOtherNodeParam<int>("stereo", "i_width");
int height = ph->getOtherNodeParam<int>("stereo", "i_height");
ptDepthInfoMan->setCameraInfo(sensor_helpers::getCalibInfo(*ptDepthImageConverter, device, socket, width, height));

ptDepthPub = it.advertiseCamera(getName() + "/passthrough_depth/image_raw", 1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include "depthai-shared/common/CameraBoardSocket.hpp"
#include "depthai/pipeline/Node.hpp"
#include "depthai_ros_driver/dai_nodes/base_node.hpp"
#include "depthai_ros_driver/dai_nodes/sensors/sensor_helpers.hpp"
#include "ros/subscriber.h"
#include "sensor_msgs/Image.h"

Expand Down Expand Up @@ -47,6 +48,7 @@ class SensorWrapper : public BaseNode {
void setNames() override;
void setXinXout(std::shared_ptr<dai::Pipeline> pipeline) override;
void closeQueues() override;
sensor_helpers::ImageSensor getSensorData();

private:
void subCB(const sensor_msgs::Image::ConstPtr& img);
Expand All @@ -59,6 +61,7 @@ class SensorWrapper : public BaseNode {
std::string inQName;
int socketID;
bool ready;
sensor_helpers::ImageSensor sensorData;
};

} // namespace dai_nodes
Expand Down
Loading

0 comments on commit d328827

Please sign in to comment.