Skip to content

Commit

Permalink
ROS 2: Merged resize.cpp: fix memory leak (#874)
Browse files Browse the repository at this point in the history
Related with this PR in ROS 1
#489

Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Jan 19, 2024
1 parent 369ce4b commit c26ba13
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 5 deletions.
2 changes: 2 additions & 0 deletions image_proc/include/image_proc/resize.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,8 @@ class ResizeNode
int height_;
int width_;

cv_bridge::CvImage scaled_cv_;

std::mutex connect_mutex_;

void connectCb();
Expand Down
12 changes: 7 additions & 5 deletions image_proc/src/resize.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,10 +86,10 @@ void ResizeNode::imageCb(
static_cast<const void *>(&(*image_msg)),
static_cast<const void *>(&(*info_msg)));

cv_bridge::CvImagePtr cv_ptr;
cv_bridge::CvImageConstPtr cv_ptr;

try {
cv_ptr = cv_bridge::toCvCopy(image_msg);
cv_ptr = cv_bridge::toCvShare(image_msg);
} catch (cv_bridge::Exception & e) {
TRACEPOINT(
image_proc_resize_fini,
Expand All @@ -102,12 +102,12 @@ void ResizeNode::imageCb(

if (use_scale_) {
cv::resize(
cv_ptr->image, cv_ptr->image, cv::Size(0, 0), scale_width_,
cv_ptr->image, scaled_cv_.image, cv::Size(0, 0), scale_width_,
scale_height_, interpolation_);
} else {
int height = height_ == -1 ? image_msg->height : height_;
int width = width_ == -1 ? image_msg->width : width_;
cv::resize(cv_ptr->image, cv_ptr->image, cv::Size(width, height), 0, 0, interpolation_);
cv::resize(cv_ptr->image, scaled_cv_.image, cv::Size(width, height), 0, 0, interpolation_);
}

sensor_msgs::msg::CameraInfo::SharedPtr dst_info_msg =
Expand Down Expand Up @@ -144,7 +144,9 @@ void ResizeNode::imageCb(
dst_info_msg->roi.width = static_cast<int>(dst_info_msg->roi.width * scale_x);
dst_info_msg->roi.height = static_cast<int>(dst_info_msg->roi.height * scale_y);

pub_image_.publish(*cv_ptr->toImageMsg(), *dst_info_msg);
scaled_cv_.header = image_msg->header;
scaled_cv_.encoding = image_msg->encoding;
pub_image_.publish(*scaled_cv_.toImageMsg(), *dst_info_msg);

TRACEPOINT(
image_proc_resize_fini,
Expand Down

0 comments on commit c26ba13

Please sign in to comment.