From e544cb9abf2c23b3dda19fd3bee4df69564dcca9 Mon Sep 17 00:00:00 2001 From: Adam Serafin Date: Fri, 1 Sep 2023 15:32:54 +0200 Subject: [PATCH] Add exposure offset (#382) --- README.md | 4 + .../include/depthai_bridge/ImageConverter.hpp | 3 + depthai_bridge/src/ImageConverter.cpp | 13 ++- depthai_bridge/src/TFPublisher.cpp | 2 +- .../dai_nodes/sensors/sensor_helpers.hpp | 4 +- .../param_handlers/stereo_param_handler.hpp | 1 + .../src/dai_nodes/sensors/mono.cpp | 4 + .../src/dai_nodes/sensors/rgb.cpp | 8 +- .../src/dai_nodes/sensors/sensor_helpers.cpp | 96 +++---------------- depthai_ros_driver/src/dai_nodes/stereo.cpp | 15 ++- .../param_handlers/sensor_param_handler.cpp | 37 ++++--- .../param_handlers/stereo_param_handler.cpp | 23 ++++- depthai_ros_driver/src/utils.cpp | 2 +- 13 files changed, 106 insertions(+), 106 deletions(-) diff --git a/README.md b/README.md index 76b38244..844825b0 100644 --- a/README.md +++ b/README.md @@ -179,6 +179,10 @@ When setting `stereo.i_align_depth: true`, stereo output is aligned to board soc You can enable rectified Stereo streams by setting, for example in the case of right stream `i_publish_right_rect: true`. You can also set `i_publish_synced_rect_pair: true` to get both images with the same timestamps. +##### Custom Sensor sockets + +Configuration of which sensors are used for computing stereo pair can be done either programatically, by specifying them in a constructor of a Stereo node (for example when building a custom pipeline), or via parameters - `stereo.i_left_socket_id`/`stereo.i_right_socket_id`. Please note that currently if you want to use rgb/center socket instead of one of the given pairs you will need to build a custom pipeline for that. + #### Feature Tracker Each sensor node (and rectified streams from Stereo node) has the option to add FeatureTracker node, which publishes `depthai_ros_msgs/msg/TrackedFeatures` messages. diff --git a/depthai_bridge/include/depthai_bridge/ImageConverter.hpp b/depthai_bridge/include/depthai_bridge/ImageConverter.hpp index 9eb54aae..e356818a 100644 --- a/depthai_bridge/include/depthai_bridge/ImageConverter.hpp +++ b/depthai_bridge/include/depthai_bridge/ImageConverter.hpp @@ -56,6 +56,7 @@ class ImageConverter { } void convertFromBitstream(dai::RawImgFrame::Type srcType); + void addExposureOffset(dai::CameraExposureOffset& offset); void convertDispToDepth(); void toRosMsg(std::shared_ptr inData, std::deque& outImageMsgs); @@ -97,6 +98,8 @@ class ImageConverter { dai::RawImgFrame::Type _srcType; bool _fromBitstream = false; bool _convertDispToDepth = false; + bool _addExpOffset = false; + dai::CameraExposureOffset _expOffset; }; } // namespace ros diff --git a/depthai_bridge/src/ImageConverter.cpp b/depthai_bridge/src/ImageConverter.cpp index ddc92846..0bc2d1a5 100644 --- a/depthai_bridge/src/ImageConverter.cpp +++ b/depthai_bridge/src/ImageConverter.cpp @@ -43,20 +43,29 @@ void ImageConverter::updateRosBaseTime() { void ImageConverter::convertFromBitstream(dai::RawImgFrame::Type srcType) { _fromBitstream = true; _srcType = srcType; - std::cout << static_cast(_srcType) << std::endl; } void ImageConverter::convertDispToDepth() { _convertDispToDepth = true; } +void ImageConverter::addExposureOffset(dai::CameraExposureOffset& offset) { + _expOffset = offset; + _addExpOffset = true; +} + ImageMsgs::Image ImageConverter::toRosMsgRawPtr(std::shared_ptr inData, const sensor_msgs::msg::CameraInfo& info) { if(_updateRosBaseTimeOnToRosMsg) { updateRosBaseTime(); } std::chrono::_V2::steady_clock::time_point tstamp; if(_getBaseDeviceTimestamp) - tstamp = inData->getTimestampDevice(); + if(_addExpOffset) + tstamp = inData->getTimestampDevice(_expOffset); + else + tstamp = inData->getTimestampDevice(); + else if(_addExpOffset) + tstamp = inData->getTimestamp(_expOffset); else tstamp = inData->getTimestamp(); ImageMsgs::Image outImageMsg; diff --git a/depthai_bridge/src/TFPublisher.cpp b/depthai_bridge/src/TFPublisher.cpp index 5c8e3d1c..ae9bd691 100644 --- a/depthai_bridge/src/TFPublisher.cpp +++ b/depthai_bridge/src/TFPublisher.cpp @@ -130,7 +130,7 @@ std::string TFPublisher::getCamSocketName(int socketNum) { std::string name; for(auto& cam : _camFeatures) { if(cam.socket == static_cast(socketNum)) { - if(cam.name == "color") { + if(cam.name == "color" || cam.name == "center") { name = "rgb"; } else { name = cam.name; diff --git a/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/sensors/sensor_helpers.hpp b/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/sensors/sensor_helpers.hpp index 230873ee..9e664a30 100644 --- a/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/sensors/sensor_helpers.hpp +++ b/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/sensors/sensor_helpers.hpp @@ -38,12 +38,14 @@ enum class RGBLinkType { video, isp, preview }; namespace sensor_helpers { struct ImageSensor { std::string name; + std::string defaultResolution; std::vector allowedResolutions; bool color; - void getSizeFromResolution(const dai::ColorCameraProperties::SensorResolution& res, int& width, int& height); }; extern std::vector availableSensors; +extern std::unordered_map stringToColorResMap; + void basicCameraPub(const std::string& /*name*/, const std::shared_ptr& data, dai::ros::ImageConverter& converter, diff --git a/depthai_ros_driver/include/depthai_ros_driver/param_handlers/stereo_param_handler.hpp b/depthai_ros_driver/include/depthai_ros_driver/param_handlers/stereo_param_handler.hpp index bcc2edbe..26182143 100644 --- a/depthai_ros_driver/include/depthai_ros_driver/param_handlers/stereo_param_handler.hpp +++ b/depthai_ros_driver/include/depthai_ros_driver/param_handlers/stereo_param_handler.hpp @@ -26,6 +26,7 @@ class StereoParamHandler : public BaseParamHandler { ~StereoParamHandler(); void declareParams(std::shared_ptr stereo, const std::vector& camFeatures); dai::CameraControl setRuntimeParams(const std::vector& params) override; + void updateSocketsFromParams(dai::CameraBoardSocket& left, dai::CameraBoardSocket& right); private: std::unordered_map depthPresetMap; diff --git a/depthai_ros_driver/src/dai_nodes/sensors/mono.cpp b/depthai_ros_driver/src/dai_nodes/sensors/mono.cpp index abfe9b39..22cb09bc 100644 --- a/depthai_ros_driver/src/dai_nodes/sensors/mono.cpp +++ b/depthai_ros_driver/src/dai_nodes/sensors/mono.cpp @@ -66,6 +66,10 @@ void Mono::setupQueues(std::shared_ptr device) { if(ph->getParam("i_low_bandwidth")) { imageConverter->convertFromBitstream(dai::RawImgFrame::Type::GRAY8); } + if(ph->getParam("i_add_exposure_offset")) { + auto offset = static_cast(ph->getParam("i_exposure_offset")); + imageConverter->addExposureOffset(offset); + } infoManager = std::make_shared( getROSNode()->create_sub_node(std::string(getROSNode()->get_name()) + "/" + getName()).get(), "/" + getName()); if(ph->getParam("i_calibration_file").empty()) { diff --git a/depthai_ros_driver/src/dai_nodes/sensors/rgb.cpp b/depthai_ros_driver/src/dai_nodes/sensors/rgb.cpp index 292673ad..6794c732 100644 --- a/depthai_ros_driver/src/dai_nodes/sensors/rgb.cpp +++ b/depthai_ros_driver/src/dai_nodes/sensors/rgb.cpp @@ -22,7 +22,7 @@ RGB::RGB(const std::string& daiNodeName, rclcpp::Node* node, std::shared_ptr pipeline, dai::CameraBoardSocket socket = dai::CameraBoardSocket::CAM_A, - sensor_helpers::ImageSensor sensor = {"IMX378", {"12mp", "4k"}, true}, + sensor_helpers::ImageSensor sensor = {"IMX378", "4k", {"12mp", "4k"}, true}, bool publish = true) : BaseNode(daiNodeName, node, pipeline) { RCLCPP_DEBUG(node->get_logger(), "Creating node %s", daiNodeName.c_str()); @@ -77,9 +77,13 @@ void RGB::setupQueues(std::shared_ptr device) { std::make_unique(tfPrefix + "_camera_optical_frame", false, ph->getParam("i_get_base_device_timestamp")); imageConverter->setUpdateRosBaseTimeOnToRosMsg(ph->getParam("i_update_ros_base_time_on_ros_msg")); if(ph->getParam("i_low_bandwidth")) { - RCLCPP_INFO(getROSNode()->get_logger(), "Low bandwidth mode enabled"); imageConverter->convertFromBitstream(dai::RawImgFrame::Type::BGR888i); } + if(ph->getParam("i_add_exposure_offset")) { + auto offset = static_cast(ph->getParam("i_exposure_offset")); + imageConverter->addExposureOffset(offset); + } + if(ph->getParam("i_calibration_file").empty()) { infoManager->setCameraInfo(sensor_helpers::getCalibInfo(getROSNode()->get_logger(), *imageConverter, diff --git a/depthai_ros_driver/src/dai_nodes/sensors/sensor_helpers.cpp b/depthai_ros_driver/src/dai_nodes/sensors/sensor_helpers.cpp index bb344fc9..9b7af0d8 100644 --- a/depthai_ros_driver/src/dai_nodes/sensors/sensor_helpers.cpp +++ b/depthai_ros_driver/src/dai_nodes/sensors/sensor_helpers.cpp @@ -9,88 +9,20 @@ namespace depthai_ros_driver { namespace dai_nodes { namespace sensor_helpers { -void ImageSensor::getSizeFromResolution(const dai::ColorCameraProperties::SensorResolution& res, int& width, int& height) { - switch(res) { - case dai::ColorCameraProperties::SensorResolution::THE_720_P: { - width = 1280; - height = 720; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_800_P: { - width = 1280; - height = 800; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_1080_P: { - width = 1920; - height = 1080; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_4_K: { - width = 3840; - height = 2160; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_12_MP: { - width = 4056; - height = 3040; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_1200_P: { - width = 1920; - height = 1200; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_5_MP: { - width = 2592; - height = 1944; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_13_MP: { - width = 4208; - height = 3120; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_4000X3000: { - width = 4000; - height = 3000; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_5312X6000: { - width = 5312; - height = 6000; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_48_MP: { - width = 8000; - height = 6000; - break; - } - case dai::ColorCameraProperties::SensorResolution::THE_1440X1080: { - width = 1440; - height = 1080; - break; - } - default: { - throw std::runtime_error("Resolution not supported!"); - } - } -} -std::vector availableSensors{ - {"IMX378", {"12mp", "4k"}, true}, - {"OV9282", {"800P", "720p", "400p"}, false}, - {"OV9782", {"800P", "720p", "400p"}, true}, - {"OV9281", {"800P", "720p", "400p"}, true}, - {"IMX214", {"13mp", "12mp", "4k", "1080p"}, true}, - {"IMX412", {"13mp", "12mp", "4k", "1080p"}, true}, - {"OV7750", {"480P", "400p"}, false}, - {"OV7251", {"480P", "400p"}, false}, - {"IMX477", {"12mp", "4k", "1080p"}, true}, - {"IMX577", {"12mp", "4k", "1080p"}, true}, - {"AR0234", {"1200P"}, true}, - {"IMX582", {"48mp", "12mp", "4k"}, true}, - {"LCM48", {"48mp", "12mp", "4k"}, true}, -}; + +std::vector availableSensors{{"IMX378", "4k", {"12mp", "4k"}, true}, + {"OV9282", "800p", {"800p", "720p", "400p"}, false}, + {"OV9782", "800p", {"800p", "720p", "400p"}, true}, + {"OV9281", "800p", {"800p", "720p", "400p"}, true}, + {"IMX214", "1080p", {"13mp", "12mp", "4k", "1080p"}, true}, + {"IMX412", "1080p", {"13mp", "12mp", "4k", "1080p"}, true}, + {"OV7750", "480p", {"480p", "400p"}, false}, + {"OV7251", "480p", {"480p", "400p"}, false}, + {"IMX477", "1080p", {"12mp", "4k", "1080p"}, true}, + {"IMX577", "1080p", {"12mp", "4k", "1080p"}, true}, + {"AR0234", "1200p", {"1200p"}, true}, + {"IMX582", "4k", {"48mp", "12mp", "4k"}, true}, + {"LCM48", "4k", {"48mp", "12mp", "4k"}, true}}; void basicCameraPub(const std::string& /*name*/, const std::shared_ptr& data, diff --git a/depthai_ros_driver/src/dai_nodes/stereo.cpp b/depthai_ros_driver/src/dai_nodes/stereo.cpp index 81470371..8cc7437a 100644 --- a/depthai_ros_driver/src/dai_nodes/stereo.cpp +++ b/depthai_ros_driver/src/dai_nodes/stereo.cpp @@ -28,6 +28,8 @@ Stereo::Stereo(const std::string& daiNodeName, : BaseNode(daiNodeName, node, pipeline) { RCLCPP_DEBUG(node->get_logger(), "Creating node %s", daiNodeName.c_str()); setNames(); + ph = std::make_unique(node, daiNodeName); + ph->updateSocketsFromParams(leftSocket, rightSocket); auto features = device->getConnectedCameraFeatures(); for(auto f : features) { if(f.socket == leftSocket) { @@ -41,7 +43,6 @@ Stereo::Stereo(const std::string& daiNodeName, stereoCamNode = pipeline->create(); left = std::make_unique(leftSensInfo.name, node, pipeline, device, leftSensInfo.socket, false); right = std::make_unique(rightSensInfo.name, node, pipeline, device, rightSensInfo.socket, false); - ph = std::make_unique(node, daiNodeName); ph->declareParams(stereoCamNode, features); setXinXout(pipeline); left->link(stereoCamNode->left); @@ -124,7 +125,11 @@ void Stereo::setupRectQueue(std::shared_ptr device, if(lowBandwidth) { conv->convertFromBitstream(dai::RawImgFrame::Type::GRAY8); } - + bool addOffset = ph->getParam(isLeft ? "i_left_rect_add_exposure_offset" : "i_right_rect_add_exposure_offset"); + if(addOffset) { + auto offset = static_cast(ph->getParam(isLeft ? "i_left_rect_exposure_offset" : "i_right_rect_exposure_offset")); + conv->addExposureOffset(offset); + } im = std::make_shared( getROSNode()->create_sub_node(std::string(getROSNode()->get_name()) + "/" + sensorInfo.name).get(), "/rect"); @@ -186,11 +191,13 @@ void Stereo::setupStereoQueue(std::shared_ptr device) { stereoConv->setUpdateRosBaseTimeOnToRosMsg(ph->getParam("i_update_ros_base_time_on_ros_msg")); if(ph->getParam("i_low_bandwidth")) { stereoConv->convertFromBitstream(dai::RawImgFrame::Type::RAW8); - RCLCPP_INFO(getROSNode()->get_logger(), "Setting stereo low bandwidth mode"); } if(!ph->getParam("i_output_disparity")) { stereoConv->convertDispToDepth(); - RCLCPP_INFO(getROSNode()->get_logger(), "Setting stereo output to depth"); + } + if(ph->getParam("i_add_exposure_offset")) { + auto offset = static_cast(ph->getParam("i_exposure_offset")); + stereoConv->addExposureOffset(offset); } stereoIM = std::make_shared( getROSNode()->create_sub_node(std::string(getROSNode()->get_name()) + "/" + getName()).get(), "/" + getName()); 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 e6026e3e..088b4e08 100644 --- a/depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp +++ b/depthai_ros_driver/src/param_handlers/sensor_param_handler.cpp @@ -29,6 +29,8 @@ void SensorParamHandler::declareCommonParams() { declareAndLogParam("i_update_ros_base_time_on_ros_msg", false); declareAndLogParam("i_enable_feature_tracker", false); declareAndLogParam("i_enable_lazy_publisher", true); + declareAndLogParam("i_add_exposure_offset", false); + declareAndLogParam("i_exposure_offset", 0); fSyncModeMap = { {"OFF", dai::CameraControl::FrameSyncMode::OFF}, {"OUTPUT", dai::CameraControl::FrameSyncMode::OUTPUT}, @@ -82,17 +84,17 @@ void SensorParamHandler::declareParams(std::shared_ptr c dai::CameraBoardSocket socket, dai_nodes::sensor_helpers::ImageSensor sensor, bool publish) { - rgbResolutionMap = {{"720", dai::ColorCameraProperties::SensorResolution::THE_720_P}, - {"1080", dai::ColorCameraProperties::SensorResolution::THE_1080_P}, - {"4K", dai::ColorCameraProperties::SensorResolution::THE_4_K}, - {"12MP", dai::ColorCameraProperties::SensorResolution::THE_12_MP}, - {"13MP", dai::ColorCameraProperties::SensorResolution::THE_13_MP}, - {"800", dai::ColorCameraProperties::SensorResolution::THE_800_P}, - {"1200", dai::ColorCameraProperties::SensorResolution::THE_1200_P}, + rgbResolutionMap = {{"720p", dai::ColorCameraProperties::SensorResolution::THE_720_P}, + {"1080p", dai::ColorCameraProperties::SensorResolution::THE_1080_P}, + {"4k", dai::ColorCameraProperties::SensorResolution::THE_4_K}, + {"12mp", dai::ColorCameraProperties::SensorResolution::THE_12_MP}, + {"13mp", dai::ColorCameraProperties::SensorResolution::THE_13_MP}, + {"800p", dai::ColorCameraProperties::SensorResolution::THE_800_P}, + {"1200p", dai::ColorCameraProperties::SensorResolution::THE_1200_P}, {"5MP", dai::ColorCameraProperties::SensorResolution::THE_5_MP}, {"4000x3000", dai::ColorCameraProperties::SensorResolution::THE_4000X3000}, {"5312X6000", dai::ColorCameraProperties::SensorResolution::THE_5312X6000}, - {"48_MP", dai::ColorCameraProperties::SensorResolution::THE_48_MP}, + {"48mp", dai::ColorCameraProperties::SensorResolution::THE_48_MP}, {"1440X1080", dai::ColorCameraProperties::SensorResolution::THE_1440X1080}}; declareAndLogParam("i_publish_topic", publish); declareAndLogParam("i_board_socket_id", static_cast(socket)); @@ -104,10 +106,21 @@ void SensorParamHandler::declareParams(std::shared_ptr c int preview_width = declareAndLogParam("i_preview_width", preview_size); int preview_height = declareAndLogParam("i_preview_height", preview_size); colorCam->setPreviewSize(preview_width, preview_height); - auto resolution = utils::getValFromMap(declareAndLogParam("i_resolution", "1080"), rgbResolutionMap); - int width, height; - colorCam->setResolution(resolution); - sensor.getSizeFromResolution(colorCam->getResolution(), width, height); + auto resString = declareAndLogParam("i_resolution", sensor.defaultResolution); + + // if resolution not in allowed resolutions, use default + if(std::find(sensor.allowedResolutions.begin(), sensor.allowedResolutions.end(), resString) == sensor.allowedResolutions.end()) { + RCLCPP_WARN(getROSNode()->get_logger(), + "Resolution %s not supported by sensor %s. Using default resolution %s", + resString.c_str(), + sensor.name.c_str(), + sensor.defaultResolution.c_str()); + resString = sensor.defaultResolution; + } + + int width = colorCam->getResolutionWidth(); + int height = colorCam->getResolutionHeight(); + colorCam->setResolution(utils::getValFromMap(resString, rgbResolutionMap)); colorCam->setInterleaved(declareAndLogParam("i_interleaved", false)); if(declareAndLogParam("i_set_isp_scale", true)) { 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 a555f21d..01a869c4 100644 --- a/depthai_ros_driver/src/param_handlers/stereo_param_handler.cpp +++ b/depthai_ros_driver/src/param_handlers/stereo_param_handler.cpp @@ -35,9 +35,24 @@ StereoParamHandler::StereoParamHandler(rclcpp::Node* node, const std::string& na {"VALID_1_IN_LAST_8", dai::StereoDepthConfig::PostProcessing::TemporalFilter::PersistencyMode::VALID_1_IN_LAST_8}, {"PERSISTENCY_INDEFINITELY", dai::StereoDepthConfig::PostProcessing::TemporalFilter::PersistencyMode::PERSISTENCY_INDEFINITELY}, }; + declareAndLogParam("i_left_socket_id", static_cast(dai::CameraBoardSocket::CAM_B)); + declareAndLogParam("i_right_socket_id", static_cast(dai::CameraBoardSocket::CAM_C)); } StereoParamHandler::~StereoParamHandler() = default; + +void StereoParamHandler::updateSocketsFromParams(dai::CameraBoardSocket& left, dai::CameraBoardSocket& right) { + int newLeftS = declareAndLogParam("i_left_socket_id", static_cast(left)); + int newRightS = declareAndLogParam("i_right_socket_id", static_cast(right)); + if(newLeftS != static_cast(left) || newRightS != static_cast(right)) { + RCLCPP_WARN(getROSNode()->get_logger(), "Left or right socket changed, updating stereo node"); + RCLCPP_WARN(getROSNode()->get_logger(), "Old left socket: %d, new left socket: %d", static_cast(left), newLeftS); + RCLCPP_WARN(getROSNode()->get_logger(), "Old right socket: %d, new right socket: %d", static_cast(right), newRightS); + } + left = static_cast(newLeftS); + right = static_cast(newRightS); +} + void StereoParamHandler::declareParams(std::shared_ptr stereo, const std::vector& camFeatures) { declareAndLogParam("i_max_q_size", 30); declareAndLogParam("i_low_bandwidth", false); @@ -46,18 +61,24 @@ void StereoParamHandler::declareParams(std::shared_ptr s declareAndLogParam("i_get_base_device_timestamp", false); declareAndLogParam("i_update_ros_base_time_on_ros_msg", false); declareAndLogParam("i_publish_topic", true); + declareAndLogParam("i_add_exposure_offset", false); + declareAndLogParam("i_exposure_offset", 0); + declareAndLogParam("i_enable_lazy_publisher", true); declareAndLogParam("i_publish_synced_rect_pair", false); declareAndLogParam("i_publish_left_rect", false); declareAndLogParam("i_left_rect_low_bandwidth", false); declareAndLogParam("i_left_rect_low_bandwidth_quality", 50); + declareAndLogParam("i_left_rect_add_exposure_offset", false); + declareAndLogParam("i_left_rect_exposure_offset", 0); declareAndLogParam("i_left_rect_enable_feature_tracker", false); declareAndLogParam("i_publish_right_rect", false); declareAndLogParam("i_right_rect_low_bandwidth", false); declareAndLogParam("i_right_rect_low_bandwidth_quality", 50); declareAndLogParam("i_right_rect_enable_feature_tracker", false); - declareAndLogParam("i_enable_lazy_publisher", true); + declareAndLogParam("i_right_rect_add_exposure_offset", false); + declareAndLogParam("i_right_rect_exposure_offset", 0); stereo->setLeftRightCheck(declareAndLogParam("i_lr_check", true)); int width = 1280; diff --git a/depthai_ros_driver/src/utils.cpp b/depthai_ros_driver/src/utils.cpp index a57ef9ac..6d50a2c5 100644 --- a/depthai_ros_driver/src/utils.cpp +++ b/depthai_ros_driver/src/utils.cpp @@ -13,7 +13,7 @@ std::string getSocketName(dai::CameraBoardSocket socket, std::vector