From aff37a13441a907851e3aaeb57a9e9eb3f8fb03c Mon Sep 17 00:00:00 2001 From: Stefan Kohlbrecher Date: Sat, 13 Feb 2016 17:32:10 +0100 Subject: [PATCH] Remove OpenMP parallelization, fixes #563 --- perception/point_containment_filter/src/shape_mask.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/perception/point_containment_filter/src/shape_mask.cpp b/perception/point_containment_filter/src/shape_mask.cpp index d40f0fdc07..b12283be99 100644 --- a/perception/point_containment_filter/src/shape_mask.cpp +++ b/perception/point_containment_filter/src/shape_mask.cpp @@ -148,7 +148,8 @@ void point_containment_filter::ShapeMask::maskContainment(const sensor_msgs::Poi sensor_msgs::PointCloud2ConstIterator iter_z(data_in, "z"); // Cloud iterators are not incremented in the for loop, because of the pragma -#pragma omp parallel for schedule(dynamic) +// Comment out below parallelization as it can result in very high CPU consumption +//#pragma omp parallel for schedule(dynamic) for (int i = 0 ; i < (int)np ; ++i) { Eigen::Vector3d pt = Eigen::Vector3d(*(iter_x+i), *(iter_y+i), *(iter_z+i));