Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix memory leaks in OpenNI apps #3553

Merged
merged 1 commit into from
Jan 16, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions apps/src/openni_3d_concave_hull.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,21 +138,21 @@ class OpenNI3DConcaveHull
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
pcl::OpenNIGrabber interface {device_id_};

std::function<void (const CloudConstPtr&)> f = [this] (const CloudConstPtr& cloud) { cloud_cb (cloud); };
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

viewer.runOnVisualizationThread ([this] (pcl::visualization::PCLVisualizer& viz) { viz_cb (viz); }, "viz_cb");

interface->start ();
interface.start ();

while (!viewer.wasStopped ())
{
std::this_thread::sleep_for(1ms);
}

interface->stop ();
interface.stop ();
}

pcl::VoxelGrid<PointType> grid;
Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_3d_convex_hull.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,21 +136,21 @@ class OpenNI3DConvexHull
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
pcl::OpenNIGrabber interface {device_id_};

std::function<void (const CloudConstPtr&)> f = [this] (const CloudConstPtr& cloud) { cloud_cb (cloud); };
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

viewer.runOnVisualizationThread ([this] (pcl::visualization::PCLVisualizer& viz) { viz_cb (viz); }, "viz_cb");

interface->start ();
interface.start ();

while (!viewer.wasStopped ())
{
std::this_thread::sleep_for(1ms);
}

interface->stop ();
interface.stop ();
}

pcl::PassThrough<PointType> pass;
Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_boundary_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,21 +157,21 @@ class OpenNIIntegralImageNormalEstimation
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
pcl::OpenNIGrabber interface {device_id_};

std::function<void (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &)> f = [this] (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud) { cloud_cb (cloud); };
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

viewer.runOnVisualizationThread ([this] (pcl::visualization::PCLVisualizer& viz) { viz_cb (viz); }, "viz_cb");

interface->start ();
interface.start ();

while (!viewer.wasStopped ())
{
std::this_thread::sleep_for(1s);
}

interface->stop ();
interface.stop ();
}

pcl::ApproximateVoxelGrid<pcl::PointXYZRGBNormal> pass_;
Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_change_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,21 +121,21 @@ class OpenNIChangeViewer
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber();
pcl::OpenNIGrabber interface {};

std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
[this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud) { cloud_cb_ (cloud); };

boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

interface->start ();
interface.start ();

while (!viewer.wasStopped())
{
std::this_thread::sleep_for(1s);
}

interface->stop ();
interface.stop ();
}

pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGBA> *octree;
Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_fast_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,14 +104,14 @@ class OpenNIFastMesh
void
run (int argc, char **argv)
{
pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
pcl::OpenNIGrabber interface {device_id_};

std::function<void (const CloudConstPtr&)> f = [this] (const CloudConstPtr& cloud) { cloud_cb (cloud); };
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

view.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCL OpenNI Mesh Viewer"));

interface->start ();
interface.start ();

CloudConstPtr temp_cloud;
std::vector<pcl::Vertices> temp_verts;
Expand All @@ -138,7 +138,7 @@ class OpenNIFastMesh
view->spinOnce (1);
}

interface->stop ();
interface.stop ();
}

pcl::OrganizedFastMesh<PointType> ofm;
Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_feature_persistence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,21 +188,21 @@ class OpenNIFeaturePersistence
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
pcl::OpenNIGrabber interface {device_id_};

std::function<void (const CloudConstPtr&)> f = [this] (const CloudConstPtr& cloud) { cloud_cb (cloud); };
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

viewer.runOnVisualizationThread ([this] (pcl::visualization::PCLVisualizer& viz) { viz_cb (viz); }, "viz_cb");

interface->start ();
interface.start ();

while (!viewer.wasStopped ())
{
std::this_thread::sleep_for(1s);
}

interface->stop ();
interface.stop ();
}


Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_ii_normal_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,21 +161,21 @@ class OpenNIIntegralImageNormalEstimation
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
pcl::OpenNIGrabber interface {device_id_};

std::function<void (const CloudConstPtr&)> f = [this] (const CloudConstPtr& cloud) { cloud_cb (cloud); };
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

viewer.runOnVisualizationThread ([this] (pcl::visualization::PCLVisualizer& viz) { viz_cb (viz); }, "viz_cb");

interface->start ();
interface.start ();

while (!viewer.wasStopped ())
{
std::this_thread::sleep_for(1s);
}

interface->stop ();
interface.stop ();
}

pcl::IntegralImageNormalEstimation<PointType, pcl::Normal> ne_;
Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_mls_smoothing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,15 +132,15 @@ class OpenNISmoothing
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
pcl::OpenNIGrabber interface {device_id_};

std::function<void (const CloudConstPtr&)> f = [this] (const CloudConstPtr& cloud) { cloud_cb_ (cloud); };
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

viewer.registerKeyboardCallback (keyboardEventOccurred, reinterpret_cast<void*> (&stop_computing_));


interface->start ();
interface.start ();

while (!viewer.wasStopped ())
{
Expand All @@ -157,7 +157,7 @@ class OpenNISmoothing
}
}

interface->stop ();
interface.stop ();
}

pcl::MovingLeastSquares<PointType, PointType> smoother_;
Expand Down
16 changes: 8 additions & 8 deletions apps/src/openni_octree_compression.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,25 +152,25 @@ class SimpleOpenNIViewer
{

// create a new grabber for OpenNI devices
pcl::Grabber* interface = new pcl::OpenNIGrabber();
pcl::OpenNIGrabber interface {};

// make callback function from member function
std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
[this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& cloud) { cloud_cb_ (cloud); };

// connect callback function for desired signal. In this case its a point cloud with color values
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

// start receiving point clouds
interface->start ();
interface.start ();


while (!outputFile_.fail())
{
std::this_thread::sleep_for(1s);
}

interface->stop ();
interface.stop ();
}

pcl::visualization::CloudViewer viewer;
Expand Down Expand Up @@ -207,7 +207,7 @@ struct EventHelper
run ()
{
// create a new grabber for OpenNI devices
pcl::Grabber* interface = new pcl::OpenNIGrabber ();
pcl::OpenNIGrabber interface {};

// make callback function from member function
std::function<void
Expand All @@ -217,17 +217,17 @@ struct EventHelper
};

// connect callback function for desired signal. In this case its a point cloud with color values
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

// start receiving point clouds
interface->start ();
interface.start ();

while (!outputFile_.fail ())
{
std::this_thread::sleep_for(1s);
}

interface->stop ();
interface.stop ();
}

pcl::PassThrough<PointXYZRGBA> pass_;
Expand Down
16 changes: 8 additions & 8 deletions apps/src/openni_organized_compression.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,25 +152,25 @@ class SimpleOpenNIViewer
if (!bRawImageEncoding_)
{
// create a new grabber for OpenNI devices
pcl::Grabber* interface = new pcl::OpenNIGrabber();
pcl::OpenNIGrabber interface {};

// make callback function from member function
std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
[this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& cloud) { cloud_cb_ (cloud); };

// connect callback function for desired signal. In this case its a point cloud with color values
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

// start receiving point clouds
interface->start ();
interface.start ();


while (!outputFile_.fail())
{
std::this_thread::sleep_for(1s);
}

interface->stop ();
interface.stop ();
}

}
Expand Down Expand Up @@ -243,7 +243,7 @@ struct EventHelper
if (!bRawImageEncoding_)
{
// create a new grabber for OpenNI devices
pcl::Grabber* interface = new pcl::OpenNIGrabber ();
pcl::OpenNIGrabber interface {};

// make callback function from member function
std::function<void
Expand All @@ -253,17 +253,17 @@ struct EventHelper
};

// connect callback function for desired signal. In this case its a point cloud with color values
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

// start receiving point clouds
interface->start ();
interface.start ();

while (!outputFile_.fail ())
{
std::this_thread::sleep_for(1s);
}

interface->stop ();
interface.stop ();
} else
{
pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_organized_edge_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,16 +143,16 @@ class OpenNIOrganizedEdgeDetection
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber ();
pcl::OpenNIGrabber interface {};

std::function<void(const pcl::PointCloud<PointT>::ConstPtr&)> f = [this] (const pcl::PointCloud<PointT>::ConstPtr& cloud) { cloud_cb_ (cloud); };

// Make and initialize a cloud viewer
pcl::PointCloud<PointT>::Ptr init_cloud_ptr (new pcl::PointCloud<PointT>);
viewer = initCloudViewer (init_cloud_ptr);
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

interface->start ();
interface.start ();

pcl::IntegralImageNormalEstimation<PointT, pcl::Normal> ne;
ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
Expand Down Expand Up @@ -245,7 +245,7 @@ class OpenNIOrganizedEdgeDetection
}
}

interface->stop ();
interface.stop ();
}
};

Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_organized_multi_plane_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,16 +109,16 @@ class OpenNIOrganizedMultiPlaneSegmentation
void
run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber ();
pcl::OpenNIGrabber interface {};

std::function<void(const pcl::PointCloud<PointT>::ConstPtr&)> f = [this] (const pcl::PointCloud<PointT>::ConstPtr& cloud) { cloud_cb_ (cloud); };

//make a viewer
pcl::PointCloud<PointT>::Ptr init_cloud_ptr (new pcl::PointCloud<PointT>);
viewer = cloudViewer (init_cloud_ptr);
boost::signals2::connection c = interface->registerCallback (f);
boost::signals2::connection c = interface.registerCallback (f);

interface->start ();
interface.start ();

unsigned char red [6] = {255, 0, 0, 255, 255, 0};
unsigned char grn [6] = { 0, 255, 0, 255, 0, 255};
Expand Down Expand Up @@ -190,7 +190,7 @@ class OpenNIOrganizedMultiPlaneSegmentation
}
}

interface->stop ();
interface.stop ();
}
};

Expand Down
Loading