Adding stereo post processing and Exposure settings to stereo inertial node#24
Adding stereo post processing and Exposure settings to stereo inertial node#24
Conversation
03c2d36 to
82e910f
Compare
82e910f to
98e46d5
Compare
There was a problem hiding this comment.
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.
| 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); | ||
| } |
There was a problem hiding this comment.
https://docs.luxonis.com/en/latest/pages/faq/?highlight=Exposure%20setting#white-balance-awb
Can you add AF, AE to the same ?
There was a problem hiding this comment.
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.
| void setMedianFilter(std::shared_ptr<dai::node::StereoDepth> stereo); | ||
|
|
||
| void setFilters(std::shared_ptr<dai::node::StereoDepth> stereo); | ||
|
|
There was a problem hiding this comment.
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 ?
There was a problem hiding this comment.
Same applies for Exposure setting.
72eeb8f to
278ef0d
Compare
| common_src/DepthPostProcessing.cpp | ||
| common_src/CameraControl.cpp) |
There was a problem hiding this comment.
Move the common libraries to depthai-ros
| 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 |
There was a problem hiding this comment.
Can you change this and use these from calibration data.
| config.postProcessing.speckleFilter.enable = this->speckle_enable; | ||
| config.postProcessing.speckleFilter.speckleRange = static_cast<std::uint32_t>(this->speckle_range); |
There was a problem hiding this comment.
Create separate functions for each type with arguments. And if it is enabled call them.
There was a problem hiding this comment.
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
There was a problem hiding this comment.
https://gist.github.com/szabi-luxonis/5f20474583ec3498b8360f6fca014d4e
Example for changing these realtime. Than initial config.
| rgb.time_us = clamp(req_get(exposure_time_us), 1, 33000); | ||
| rgb.sensitivity_iso = clamp(req_get(exposure_time_us), 1, 33000); |
There was a problem hiding this comment.
@alex-luxonis Is this the same for all modules or can we fetch this from device and set the limits based on the CCM ?
a0f22d3 to
e8cf706
Compare
Add optional parameters to all ROS1 nodes
Add post-processing and exposure settings
Add and apply clang-format