From f4c7dd88f6534ad922c29467817ac28f380310f0 Mon Sep 17 00:00:00 2001 From: Arun-Prasad-V Date: Tue, 13 Jun 2023 05:28:05 +0530 Subject: [PATCH] Applying AlignDepth filter after Pointcloud --- realsense2_camera/src/base_realsense_node.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/realsense2_camera/src/base_realsense_node.cpp b/realsense2_camera/src/base_realsense_node.cpp index 310bb25bd5..bf44d360b2 100755 --- a/realsense2_camera/src/base_realsense_node.cpp +++ b/realsense2_camera/src/base_realsense_node.cpp @@ -195,14 +195,15 @@ void BaseRealSenseNode::setupFilters() } _cv_mpc.notify_one(); }; - _align_depth_filter = std::make_shared(std::make_shared(RS2_STREAM_COLOR), update_align_depth_func, _parameters, _logger); - _filters.push_back(_align_depth_filter); _colorizer_filter = std::make_shared(std::make_shared(), _parameters, _logger); _filters.push_back(_colorizer_filter); _pc_filter = std::make_shared(std::make_shared(), _node, _parameters, _logger); _filters.push_back(_pc_filter); + + _align_depth_filter = std::make_shared(std::make_shared(RS2_STREAM_COLOR), update_align_depth_func, _parameters, _logger); + _filters.push_back(_align_depth_filter); } cv::Mat& BaseRealSenseNode::fix_depth_scale(const cv::Mat& from_image, cv::Mat& to_image)