diff --git a/realsense2_camera/src/base_realsense_node.cpp b/realsense2_camera/src/base_realsense_node.cpp index bae5fe6f83..cae3f6c43f 100755 --- a/realsense2_camera/src/base_realsense_node.cpp +++ b/realsense2_camera/src/base_realsense_node.cpp @@ -818,7 +818,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); }