Skip to content

Commit

Permalink
Added GL support for Align-Depth filter
Browse files Browse the repository at this point in the history
  • Loading branch information
Arun-Prasad-V committed Jan 19, 2024
1 parent 78b58d1 commit d6417d9
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 8 deletions.
6 changes: 3 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -355,10 +355,10 @@ User can set the camera name and camera namespace, to distinguish between camera
- 0 or negative values mean no diagnostics topic is published. Defaults to 0.</br>
The `/diagnostics` topic includes information regarding the device temperatures and actual frequency of the enabled streams.
- **accelerate_with_gpu**:
- GPU accelerated processing of PointCloud and Colorizer filters.
- GPU accelerated processing of PointCloud, Align-Depth and Colorizer filters.
- integer:
- 0 --> **NO_GPU**: use only CPU for proccessing PointCloud and Colorizer filters
- 1 --> **GL_GPU**: use GLSL to accelerate GPU for processing PointCloud and Colorizer filters
- 0 --> **NO_GPU**: use only CPU for proccessing PointCloud, Align-Depth and Colorizer filters
- 1 --> **GL_GPU**: use GLSL to accelerate GPU for processing PointCloud, Align-Depth and Colorizer filters
- Note: To enable GPU acceleration, turn ON `BUILD_ACCELERATE_WITH_GPU` during build:
```bash
colcon build --cmake-args '-DBUILD_ACCELERATE_WITH_GPU=ON'
Expand Down
6 changes: 2 additions & 4 deletions realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,18 +238,16 @@ void BaseRealSenseNode::setupFilters()

#if defined (ACCELERATE_WITH_GPU)
_colorizer_filter = std::make_shared<NamedFilter>(std::make_shared<rs2::gl::colorizer>(), _parameters, _logger);

_pc_filter = std::make_shared<PointcloudFilter>(std::make_shared<rs2::gl::pointcloud>(), _node, _parameters, _logger);
_align_depth_filter = std::make_shared<AlignDepthFilter>(std::make_shared<rs2::gl::align>(RS2_STREAM_COLOR), update_align_depth_func, _parameters, _logger);
#else
_colorizer_filter = std::make_shared<NamedFilter>(std::make_shared<rs2::colorizer>(), _parameters, _logger);

_pc_filter = std::make_shared<PointcloudFilter>(std::make_shared<rs2::pointcloud>(), _node, _parameters, _logger);
_align_depth_filter = std::make_shared<AlignDepthFilter>(std::make_shared<rs2::align>(RS2_STREAM_COLOR), update_align_depth_func, _parameters, _logger);
#endif

_filters.push_back(_colorizer_filter);
_filters.push_back(_pc_filter);

_align_depth_filter = std::make_shared<AlignDepthFilter>(std::make_shared<rs2::align>(RS2_STREAM_COLOR), update_align_depth_func, _parameters, _logger);
_filters.push_back(_align_depth_filter);
}

Expand Down
3 changes: 2 additions & 1 deletion realsense2_camera/src/gl_gpu_processing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ void BaseRealSenseNode::initOpenGLProcessing(bool use_gpu_processing)
// Pass our window to enable sharing of textures between processed frames and the window
// The "use_gpu_processing" is going to control if we will use CPU or GPU for data processing
rs2::gl::init_processing(_app, use_gpu_processing);
rs2::gl::init_rendering();

_timer = _node.create_wall_timer(1000ms, std::bind(&BaseRealSenseNode::glfwPollEventCallback, this));
}
Expand All @@ -38,7 +39,7 @@ void BaseRealSenseNode::glfwPollEventCallback()

void BaseRealSenseNode::shutdownOpenGLProcessing()
{
rs2::gl::shutdown_processing();

}

#endif

0 comments on commit d6417d9

Please sign in to comment.