Skip to content

Commit

Permalink
Merge pull request moveit#644 from skohlbr/indigo-devel
Browse files Browse the repository at this point in the history
Remove OpenMP parallelization, fixes moveit#563
  • Loading branch information
mikeferguson committed Feb 13, 2016
2 parents 7c53d2b + aff37a1 commit 72d8edb
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion perception/point_containment_filter/src/shape_mask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,8 @@ void point_containment_filter::ShapeMask::maskContainment(const sensor_msgs::Poi
sensor_msgs::PointCloud2ConstIterator<float> 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));
Expand Down

0 comments on commit 72d8edb

Please sign in to comment.