[ros-users] cvBridge + opencv memory leak problem
Patrick Mihelich
mihelich at willowgarage.com
Sun May 23 00:20:40 UTC 2010
In your example, im_left is owned by left_bridge and should not be released.
However any images you create yourself do need to be released. The memory
leak is from not releasing "test".
The original OpenCV C
API<http://opencv.willowgarage.com/documentation/c/index.html>works
with IplImage's. The new C++
API <http://opencv.willowgarage.com/documentation/cpp/index.html> cv::Mat is
easier to use and avoids having to release memory manually.
cv_bridge only uses IplImage because it predates the OpenCV C++ API. The
next revision of cv_bridge will likely use cv::Mat, precisely to avoid this
sort of confusion.
Patrick
On Sat, May 22, 2010 at 4:54 PM, chriss lei <lei.chriss at gmail.com> wrote:
>
> Hello Radu,
>
> I'm well aware of using cvReleaseImage..
> Memory leak happens even if I use a single function on IplImage converted
> from sensor_msgs.
> Here's my callback function to illustrate. Usage of cvCopy here introduces
> memory blowup problem.
>
> void callback(const sensor_msgs::CameraInfo::ConstPtr& info,
> const sensor_msgs::ImageConstPtr& left,
> const stereo_msgs::DisparityImageConstPtr&
> disparity_msg)
> {
>
> im_left = left_bridge.imgMsgToCv(left, "passthrough");
>
> disp_bridge.fromImage(disparity_msg->image, "passthrough");
> dispImg = disp_bridge.toIpl();
>
> cvShowImage("left", im_left);
>
> IplImage* test = NULL;
> test = cvCreateImage(cvGetSize(dispImg), dispImg->depth, 1);
> cvCopy(dispImg, test);
> cvShowImage("disp", test);
> }
>
> Also, I'm not supposed to deallocate any IplImages that are converted from
> sensor_msgs as described in cvBridge tutorial.
> Is there a way to use opencv functions on IplImages and not use cv::Mat ?
>
> --
> View this message in context:
> http://ros-users.122217.n3.nabble.com/cvBridge-opencv-memory-leak-problem-tp837144p837162.html
> Sent from the ROS-Users mailing list archive at Nabble.com.
>
>
> ------------------------------------------------------------------------------
>
> _______________________________________________
> ros-users mailing list
> ros-users at lists.sourceforge.net
> https://lists.sourceforge.net/lists/listinfo/ros-users
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100522/71e9ce61/attachment-0003.html>
More information about the ros-users
mailing list