Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[ros2-development] Fix overriding frames on same topics/CV-images due to a bug in PR2759 #2799

Merged
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
11 changes: 8 additions & 3 deletions realsense2_camera/include/base_realsense_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -206,9 +206,14 @@ namespace realsense2_camera

IMUInfo getImuInfo(const rs2::stream_profile& profile);

void publishFrame(rs2::frame f, const rclcpp::Time& t,
const stream_index_pair& stream,
const bool is_publishMetadata = true);
void publishFrame(rs2::frame f,
const rclcpp::Time& t,
const stream_index_pair& stream,
std::map<stream_index_pair, cv::Mat>& images,
const std::map<stream_index_pair, rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr>& info_publishers,
const std::map<stream_index_pair, std::shared_ptr<image_publisher>>& image_publishers,
const bool is_publishMetadata = true);

void publishMetadata(rs2::frame f, const rclcpp::Time& header_time, const std::string& frame_id);

sensor_msgs::msg::Imu CreateUnitedMessage(const CimuData accel_data, const CimuData gyro_data);
Expand Down
23 changes: 13 additions & 10 deletions realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -534,11 +534,11 @@ void BaseRealSenseNode::frame_callback(rs2::frame frame)
sent_depth_frame = true;
if (original_color_frame && _align_depth_filter->is_enabled())
{
publishFrame(f, t, COLOR, false);
publishFrame(f, t, COLOR, _depth_aligned_image, _depth_aligned_info_publisher, _depth_aligned_image_publishers, false);
continue;
}
}
publishFrame(f, t, sip);
publishFrame(f, t, sip, _images, _info_publishers, _image_publishers);
}
if (original_depth_frame && _align_depth_filter->is_enabled())
{
Expand All @@ -548,7 +548,7 @@ void BaseRealSenseNode::frame_callback(rs2::frame frame)
else
frame_to_send = original_depth_frame;

publishFrame(frame_to_send, t, DEPTH);
publishFrame(frame_to_send, t, DEPTH, _images, _info_publishers, _image_publishers);
}
}
else if (frame.is<rs2::video_frame>())
Expand All @@ -566,8 +566,8 @@ void BaseRealSenseNode::frame_callback(rs2::frame frame)
clip_depth(frame, _clipping_distance);
}
}
publishFrame(frame, t, sip);
}
publishFrame(frame, t, sip, _images, _info_publishers, _image_publishers);
}
_synced_imu_publisher->Resume();
} // frame_callback

Expand Down Expand Up @@ -820,6 +820,9 @@ IMUInfo BaseRealSenseNode::getImuInfo(const rs2::stream_profile& profile)

void BaseRealSenseNode::publishFrame(rs2::frame f, const rclcpp::Time& t,
const stream_index_pair& stream,
std::map<stream_index_pair, cv::Mat>& images,
const std::map<stream_index_pair, rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr>& info_publishers,
const std::map<stream_index_pair, std::shared_ptr<image_publisher>>& image_publishers,
const bool is_publishMetadata)
{
ROS_DEBUG("publishFrame(...)");
Expand All @@ -833,7 +836,7 @@ void BaseRealSenseNode::publishFrame(rs2::frame f, const rclcpp::Time& t,
height = timage.get_height();
bpp = timage.get_bytes_per_pixel();
}
auto& image = _images[stream];
auto& image = images[stream];

if (image.size() != cv::Size(width, height) || image.depth() != _image_formats[bpp])
{
Expand All @@ -846,14 +849,14 @@ void BaseRealSenseNode::publishFrame(rs2::frame f, const rclcpp::Time& t,
image = fix_depth_scale(image, _depth_scaled_image[stream]);
}

if (_info_publishers.find(stream) == _info_publishers.end() ||
_image_publishers.find(stream) == _image_publishers.end())
if (info_publishers.find(stream) == info_publishers.end() ||
image_publishers.find(stream) == image_publishers.end())
{
// Stream is already disabled.
return;
}
auto& info_publisher = _info_publishers.at(stream);
auto& image_publisher = _image_publishers.at(stream);
auto& info_publisher = info_publishers.at(stream);
auto& image_publisher = image_publishers.at(stream);
if(0 != info_publisher->get_subscription_count() ||
0 != image_publisher->get_subscription_count())
{
Expand Down