ros-visualization / rviz

ROS 3D Robot Visualizer
BSD 3-Clause "New" or "Revised" License
795 stars 459 forks source link

Memory leak when displaying DepthCloud and showing the 'Add' menu #868

Open cdondrup opened 9 years ago

cdondrup commented 9 years ago

We experienced a severe memory leak in rviz today. Here is the problem, we are displaying a DepthCloud using a depth and color image, from a rosbag at normal speed. As soon as I press the 'Add' button to add another visualisation the GUI stops updating and the memory usage increase rapidly, i.e. ~500MB per second. This is the reason for our laptop with very little memory, to freeze immediately. If the DepthCloud is turned off, no such behaviour can be observed. This only happens with the DepthCloud as far as we can say. Not sure about point clouds.

We are running 14.04 64bit and ROS Indigo. rviz: version 1.11.7 (indigo) compiled against OGRE version 1.8.1 (Byatis).

trainman419 commented 9 years ago

It's likely that the depth display is queueing messages. If it has a queue size option in the UI, you should decrease it and confirm that that fixes your problem.

If it doesn't have a queue size option, that's a bug, and one should be added.

trainman419 commented 9 years ago

I just checked the DepthCloud plugin and confirmed that it has a Queue Size option. You should try decreasing it.

cdondrup commented 9 years ago

Sorry for the late reply. Set it to 1. Same issue. The default, which I used before, is 5. So even it would queue up 5 point clouds, that should not result in overloading 16GB of RAM in a few seconds. As I said, the laptop dies instantly, swapping itself to death.

wjwwood commented 9 years ago

Ok, thanks @trainman419 and @cdondrup for looking into this. I'll try to reproduce it in the near future, maybe next week.

caguero commented 9 years ago

I managed to reproduce the issue on Ubuntu 14.04 and rviz (indigo_devel, 11fcdadbbcc4c9d38a0bd4d580be6f0b49cbbc47). DepthCloudDisplay::processMessage() calls pointcloud_common_->addMessage(cloud_msg) to queue a new point cloud message.DepthCloudDisplay::update() consumes the message. When you press the 'Add' button, the code keeps queuing messages but nobody consumes them, so the vector grows forever.

Below you can find a workaround that works for me.

diff --git a/src/rviz/default_plugin/point_cloud_common.cpp b/src/rviz/default_plugin/point_cloud_common.cpp
index 4549d86..fc6c0e2 100644
--- a/src/rviz/default_plugin/point_cloud_common.cpp
+++ b/src/rviz/default_plugin/point_cloud_common.cpp
@@ -309,6 +309,7 @@ void PointCloudCommon::CloudInfo::clear()

 PointCloudCommon::PointCloudCommon( Display* display )
 : spinner_(1, &cbqueue_)
+, queue_size(5)
 , new_xyz_transformer_(false)
 , new_color_transformer_(false)
 , needs_retransform_(false)
@@ -724,7 +725,13 @@ void PointCloudCommon::processMessage(const sensor_msgs::PointCloud2ConstPtr& cl
   if (transformCloud(info, true))
   {
     boost::mutex::scoped_lock lock(new_clouds_mutex_);
+
+    // The vector is full, remove the oldest element.
+    if (new_cloud_infos_.size() >= this->queue_size)
+      new_cloud_infos_.erase(new_cloud_infos_.begin());
+
     new_cloud_infos_.push_back(info);
+
     display_->emitTimeSignal( cloud->header.stamp );
   }
 }
diff --git a/src/rviz/default_plugin/point_cloud_common.h b/src/rviz/default_plugin/point_cloud_common.h
index 20d47d6..0bdd7e9 100644
--- a/src/rviz/default_plugin/point_cloud_common.h
+++ b/src/rviz/default_plugin/point_cloud_common.h
@@ -188,6 +188,7 @@ private:
   Ogre::SceneNode* scene_node_;

   V_CloudInfo new_cloud_infos_;
+  size_t queue_size;
   boost::mutex new_clouds_mutex_;

   L_CloudInfo obsolete_cloud_infos_;
@@ -209,6 +210,7 @@ private:
   bool new_color_transformer_;
   bool needs_retransform_;

+
   pluginlib::ClassLoader<PointCloudTransformer>* transformer_class_loader_;

   Display* display_;
cdondrup commented 9 years ago

@caguero thank you for taking that up!

wjwwood commented 9 years ago

@cdondrup after discussing it with @caguero I'm going to take some more time to look into the root cause of the issue, but please feel free to use his patch above as a workaround.

I'll try to make a complete fix asap.

wxmerkt commented 9 years ago

We experience a similar issue when playing back a PointCloud2 from a rosbag file independent of the playback speed. The PointCloud2 is being displayed on a moving tf transform, which is also played back from the log file (using rosparam set use_sim_time true). We do not have the add menu open, but several items (2 PointCloud2s, one MarkerArray) being displayed.

chukcha2 commented 7 years ago

We also experienced a similar issue displaying PointCloud2. The work around did not seem to help.