Skip to content

Commit

Permalink
PointCloud display: fix memory leak in case of constant /clock (#1412)
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke authored Sep 1, 2019
1 parent b78716d commit 04bb83d
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions src/rviz/default_plugin/point_cloud_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -532,15 +532,15 @@ void PointCloudCommon::update(float wall_dt, float ros_dt)
// and put them into obsolete_cloud_infos, so active selections
// are preserved

ros::Time now = ros::Time::now();
auto now_sec = ros::Time::now().toSec();

// if decay time == 0, clear the old cloud when we get a new one
// otherwise, clear all the outdated ones
{
boost::mutex::scoped_lock lock(new_clouds_mutex_);
if ( point_decay_time > 0.0 || !new_cloud_infos_.empty() )
{
while( !cloud_infos_.empty() && now.toSec() - cloud_infos_.front()->receive_time_.toSec() > point_decay_time )
while( !cloud_infos_.empty() && now_sec - cloud_infos_.front()->receive_time_.toSec() >= point_decay_time )
{
cloud_infos_.front()->clear();
obsolete_cloud_infos_.push_back( cloud_infos_.front() );
Expand Down Expand Up @@ -581,7 +581,7 @@ void PointCloudCommon::update(float wall_dt, float ros_dt)

V_CloudInfo::iterator next = it; next++;
// ignore point clouds that are too old, but keep at least one
if ( next != end && now.toSec() - cloud_info->receive_time_.toSec() > point_decay_time ) {
if ( next != end && now_sec - cloud_info->receive_time_.toSec() >= point_decay_time ) {
continue;
}

Expand Down

0 comments on commit 04bb83d

Please sign in to comment.