Skip to content

Adding stereo post processing and Exposure settings to stereo inertial node#24

Open
daxoft wants to merge 32 commits intomainfrom
daxoft/optional-parameters
Open

Adding stereo post processing and Exposure settings to stereo inertial node#24
daxoft wants to merge 32 commits intomainfrom
daxoft/optional-parameters

Conversation

@daxoft
Copy link
Copy Markdown
Contributor

@daxoft daxoft commented Mar 4, 2022

Add optional parameters to all ROS1 nodes
Add post-processing and exposure settings
Add and apply clang-format

@daxoft daxoft requested a review from saching13 March 4, 2022 17:30
@daxoft daxoft force-pushed the daxoft/optional-parameters branch from 03c2d36 to 82e910f Compare March 4, 2022 17:47
@daxoft daxoft force-pushed the daxoft/optional-parameters branch from 82e910f to 98e46d5 Compare March 4, 2022 17:50
@saching13 saching13 changed the base branch from main to devel March 15, 2022 16:10
Copy link
Copy Markdown
Contributor

@saching13 saching13 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Amazing PR. Love all the changes and common functions.
LMK when you address the comments.

And also there has been some changes in the previous update which might break some stuff. So need to update this accordingly. the main difference is that dequeu<msgs> is used in the converter which needed change in the way some converters are initialized. Changes are done such a way that API on the external side shouldn't be affected unless overlading binding function is used.

Comment on lines +3 to +18
void ExposureSettings::setExposure(dai::Device& device) {
auto controlQueue = device.getInputQueue("control");
auto configQueue = device.getInputQueue("config");
dai::CameraControl ctrl;
if(auto_exposure) {
ctrl.setAutoExposureEnable();
} else {
ctrl.setManualExposure(exposure_time_us, sensitivity_iso);
if(exposure_region.at(2) != 0 || exposure_region.at(3) != 0) {
dai::ImageManipConfig cfg;
cfg.setCropRect(exposure_region.at(0), exposure_region.at(1), exposure_region.at(2), exposure_region.at(3));
configQueue->send(cfg);
}
}
controlQueue->send(ctrl);
}
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can we add this also in such a way that it can be changed live using dynamic reconfigure and using services?

That would be a great addition to some of the users who wants to test with different settings and stop at one which works best for them.

Comment thread depthai_examples/ros1_src/mobilenet_publisher.cpp
Comment thread depthai_examples/include/common.hpp Outdated
Comment thread depthai_examples/include/common.hpp Outdated
Comment on lines +38 to +41
void setMedianFilter(std::shared_ptr<dai::node::StereoDepth> stereo);

void setFilters(std::shared_ptr<dai::node::StereoDepth> stereo);

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks good for the init time settings.
But to modify these at the run time create a function to share the pointer of the device to this class using setDevice for example after the device is initialized. And when setDecimationFilter(...) is called from a service or dynamic reconfigure it modifes it.

Thoughts ?

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same applies for Exposure setting.

Comment thread depthai_examples/include/common.hpp Outdated
@daxoft daxoft force-pushed the daxoft/optional-parameters branch from 72eeb8f to 278ef0d Compare March 28, 2022 16:23
@saching13 saching13 changed the title Daxoft/optional parameters Adding stereo post processing and Exposure settings to stereo inertial node Mar 28, 2022
Comment thread depthai_examples/CMakeLists.txt Outdated
Comment thread depthai_examples/CMakeLists.txt Outdated
Comment thread depthai_examples/CMakeLists.txt Outdated
Comment thread depthai_examples/CMakeLists.txt Outdated
Comment on lines +100 to +101
common_src/DepthPostProcessing.cpp
common_src/CameraControl.cpp)
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Move the common libraries to depthai-ros

Comment thread depthai_examples/CMakeLists.txt Outdated
Comment thread depthai_examples/ros1_src/stereo_inertial_publisher.cpp Outdated
std::string tfSuffix = depth_aligned ? "_rgb_camera_optical_frame" : "_right_camera_optical_frame";
dai::rosBridge::DisparityConverter dispConverter(tfPrefix + tfSuffix , 880, 7.5, 20, 2000); // TODO(sachin): undo hardcoding of baseline
auto disparityCameraInfo = depth_aligned ? rgbConverter.calibrationToCameraInfo(calibrationHandler, dai::CameraBoardSocket::RGB, 1280, 720) : rightCameraInfo;
dai::rosBridge::DisparityConverter dispConverter(tfPrefix + tfSuffix, 880, 7.5, 20, 2000); // TODO(sachin): undo hardcoding of baseline
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you change this and use these from calibration data.

Comment thread depthai_examples/ros2_src/stereo_inertial_publisher.cpp Outdated
Comment thread depthai_examples/ros2_src/stereo_inertial_publisher.cpp Outdated
Comment on lines +41 to +42
config.postProcessing.speckleFilter.enable = this->speckle_enable;
config.postProcessing.speckleFilter.speckleRange = static_cast<std::uint32_t>(this->speckle_range);
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Create separate functions for each type with arguments. And if it is enabled call them.

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

And create services on top of them for each of these settings.
And maybe use dynamic reconfigure for it?
http://wiki.ros.org/dynamic_reconfigure/Tutorials/SettingUpDynamicReconfigureForANode%28cpp%29

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

https://gist.github.com/szabi-luxonis/5f20474583ec3498b8360f6fca014d4e

Example for changing these realtime. Than initial config.

Comment on lines +87 to +88
rgb.time_us = clamp(req_get(exposure_time_us), 1, 33000);
rgb.sensitivity_iso = clamp(req_get(exposure_time_us), 1, 33000);
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@alex-luxonis Is this the same for all modules or can we fetch this from device and set the limits based on the CCM ?

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll investigate

@daxoft daxoft force-pushed the daxoft/optional-parameters branch from a0f22d3 to e8cf706 Compare April 1, 2022 15:30
Base automatically changed from devel to main May 20, 2022 04:13
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants