Skip to content

Commit

Permalink
patch realsense2_camera \n\n IntelRealSense/realsense-ros#2868
Browse files Browse the repository at this point in the history
  • Loading branch information
tingfan wu committed Oct 7, 2023
1 parent 4f331d1 commit 30e64e5
Showing 1 changed file with 12 additions and 0 deletions.
12 changes: 12 additions & 0 deletions patch/ros-humble-realsense2-camera.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
diff --git a/src/base_realsense_node.cpp b/src/base_realsense_node.cpp
index 5e4e6e7..59cf468 100755
--- a/src/base_realsense_node.cpp
+++ b/src/base_realsense_node.cpp
@@ -784,7 +784,7 @@ void BaseRealSenseNode::SetBaseStream()

void BaseRealSenseNode::publishPointCloud(rs2::points pc, const rclcpp::Time& t, const rs2::frameset& frameset)
{
- std::string frame_id = (_align_depth_filter->is_enabled() ? OPTICAL_FRAME_ID(COLOR) : OPTICAL_FRAME_ID(DEPTH));
+ std::string frame_id = OPTICAL_FRAME_ID(DEPTH);
_pc_filter->Publish(pc, t, frameset, frame_id);
}

0 comments on commit 30e64e5

Please sign in to comment.