Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
add new overloading namedFilter::process() method to enable processin…
…g frame instead of frameset

and fixing frame assignment before publishing colorized depth topic
  • Loading branch information
SamerKhshiboun committed Apr 27, 2022
commit a7e7deb1aaa2e732c1588edf595dd956315411fc
1 change: 1 addition & 0 deletions realsense2_camera/include/named_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ namespace realsense2_camera
NamedFilter(std::shared_ptr<rs2::filter> filter, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, bool is_enabled=false, bool is_set_parameters=true);
bool is_enabled() {return _is_enabled;};
rs2::frameset Process(rs2::frameset frameset);
rs2::frame Process(rs2::frame frame);

protected:
void setParameters(std::function<void(const rclcpp::Parameter&)> enable_param_func = std::function<void(const rclcpp::Parameter&)>());
Expand Down
8 changes: 6 additions & 2 deletions realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -601,9 +601,13 @@ void BaseRealSenseNode::frame_callback(rs2::frame frame)
}
if (original_depth_frame && _align_depth_filter->is_enabled())
{
rs2::frame frame_to_send;
if (_colorizer_filter->is_enabled())
original_depth_frame = _colorizer_filter->Process(original_depth_frame);
publishFrame(original_depth_frame, t,
frame_to_send = _colorizer_filter->Process(original_depth_frame);
else
frame_to_send = original_depth_frame;

publishFrame(frame_to_send, t,
DEPTH,
_image,
_info_publisher,
Expand Down
12 changes: 12 additions & 0 deletions realsense2_camera/src/named_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,18 @@ rs2::frameset NamedFilter::Process(rs2::frameset frameset)
}
}

rs2::frame NamedFilter::Process(rs2::frame frame)
{
if (_is_enabled)
{
return _filter->process(frame);
}
else
{
return frame;
}
}


PointcloudFilter::PointcloudFilter(std::shared_ptr<rs2::filter> filter, rclcpp::Node& node, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, bool is_enabled):
NamedFilter(filter, parameters, logger, is_enabled, false),
Expand Down