Skip to content

Commit

Permalink
resize.cpp: fix memory leak (#489)
Browse files Browse the repository at this point in the history
  • Loading branch information
furushchev authored and Joshua Whitley committed Jan 7, 2020
1 parent 00e7c02 commit b51c168
Showing 1 changed file with 8 additions and 5 deletions.
13 changes: 8 additions & 5 deletions image_proc/src/nodelets/resize.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ class ResizeNodelet : public nodelet::Nodelet
typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
std::shared_ptr<ReconfigureServer> reconfigure_server_;
Config config_;
cv_bridge::CvImage scaled_cv_;

virtual void onInit();
void connectCb();
Expand Down Expand Up @@ -173,10 +174,10 @@ void ResizeNodelet::imageCb(const sensor_msgs::ImageConstPtr& image_msg)
config = config_;
}

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)
{
Expand All @@ -186,17 +187,19 @@ void ResizeNodelet::imageCb(const sensor_msgs::ImageConstPtr& image_msg)

if (config.use_scale)
{
cv::resize(cv_ptr->image, cv_ptr->image, cv::Size(0, 0), config.scale_width, config.scale_height,
cv::resize(cv_ptr->image, scaled_cv_.image, cv::Size(0, 0), config.scale_width, config.scale_height,
config.interpolation);
}
else
{
int height = config.height == -1 ? image_msg->height : config.height;
int width = config.width == -1 ? image_msg->width : config.width;
cv::resize(cv_ptr->image, cv_ptr->image, cv::Size(width, height), 0, 0, config.interpolation);
cv::resize(cv_ptr->image, scaled_cv_.image, cv::Size(width, height), 0, 0, config.interpolation);
}

pub_image_.publish(cv_ptr->toImageMsg());
scaled_cv_.header = image_msg->header;
scaled_cv_.encoding = image_msg->encoding;
pub_image_.publish(scaled_cv_.toImageMsg());
}

} // namespace image_proc
Expand Down

0 comments on commit b51c168

Please sign in to comment.